|
|
|
@ -451,6 +451,7 @@ void SimpleMissionItem::_rebuildTextFieldFacts(void)
@@ -451,6 +451,7 @@ void SimpleMissionItem::_rebuildTextFieldFacts(void)
|
|
|
|
|
|
|
|
|
|
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command); |
|
|
|
|
|
|
|
|
|
if (uiInfo) { |
|
|
|
|
for (int i=1; i<=7; i++) { |
|
|
|
|
bool showUI; |
|
|
|
|
const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI); |
|
|
|
@ -466,6 +467,7 @@ void SimpleMissionItem::_rebuildTextFieldFacts(void)
@@ -466,6 +467,7 @@ void SimpleMissionItem::_rebuildTextFieldFacts(void)
|
|
|
|
|
_textFieldFacts.append(paramFact); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
_ignoreDirtyChangeSignals = false; |
|
|
|
|
} |
|
|
|
@ -490,6 +492,7 @@ void SimpleMissionItem::_rebuildNaNFacts(void)
@@ -490,6 +492,7 @@ void SimpleMissionItem::_rebuildNaNFacts(void)
|
|
|
|
|
|
|
|
|
|
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command); |
|
|
|
|
|
|
|
|
|
if (uiInfo) { |
|
|
|
|
for (int i=1; i<=7; i++) { |
|
|
|
|
bool showUI; |
|
|
|
|
const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI); |
|
|
|
@ -512,6 +515,7 @@ void SimpleMissionItem::_rebuildNaNFacts(void)
@@ -512,6 +515,7 @@ void SimpleMissionItem::_rebuildNaNFacts(void)
|
|
|
|
|
_nanFacts.append(paramFact); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
_ignoreDirtyChangeSignals = false; |
|
|
|
|
} |
|
|
|
@ -778,7 +782,8 @@ void SimpleMissionItem::_sendFriendlyEditAllowedChanged(void)
@@ -778,7 +782,8 @@ void SimpleMissionItem::_sendFriendlyEditAllowedChanged(void)
|
|
|
|
|
|
|
|
|
|
QString SimpleMissionItem::category(void) const |
|
|
|
|
{ |
|
|
|
|
return _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, static_cast<MAV_CMD>(command()))->category(); |
|
|
|
|
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, static_cast<MAV_CMD>(command())); |
|
|
|
|
return uiInfo ? uiInfo->category() : QString(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void SimpleMissionItem::setCommand(int command) |
|
|
|
@ -923,7 +928,7 @@ void SimpleMissionItem::applyNewAltitude(double newAltitude)
@@ -923,7 +928,7 @@ void SimpleMissionItem::applyNewAltitude(double newAltitude)
|
|
|
|
|
MAV_CMD command = static_cast<MAV_CMD>(this->command()); |
|
|
|
|
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command); |
|
|
|
|
|
|
|
|
|
if (uiInfo->specifiesCoordinate() || uiInfo->specifiesAltitudeOnly()) { |
|
|
|
|
if (uiInfo && (uiInfo->specifiesCoordinate() || uiInfo->specifiesAltitudeOnly())) { |
|
|
|
|
switch (static_cast<MAV_CMD>(this->command())) { |
|
|
|
|
case MAV_CMD_NAV_LAND: |
|
|
|
|
case MAV_CMD_NAV_VTOL_LAND: |
|
|
|
@ -989,9 +994,7 @@ void SimpleMissionItem::_possibleAdditionalTimeDelayChanged(void)
@@ -989,9 +994,7 @@ void SimpleMissionItem::_possibleAdditionalTimeDelayChanged(void)
|
|
|
|
|
|
|
|
|
|
bool SimpleMissionItem::isLandCommand(void) const |
|
|
|
|
{ |
|
|
|
|
MAV_CMD command = static_cast<MAV_CMD>(this->command()); |
|
|
|
|
const MissionCommandUIInfo* uiInfo = _commandTree->getUIInfo(_controllerVehicle, _previousVTOLMode, command); |
|
|
|
|
return uiInfo->isLandCommand(); |
|
|
|
|
return _commandTree->isLandCommand(static_cast<MAV_CMD>(this->command())); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
QGeoCoordinate SimpleMissionItem::coordinate(void) const |
|
|
|
|