16#include <QtCore/QStringList>
17#include <QtCore/QJsonArray>
19FactMetaData* SimpleMissionItem::_altitudeMetaData =
nullptr;
20FactMetaData* SimpleMissionItem::_commandMetaData =
nullptr;
21FactMetaData* SimpleMissionItem::_defaultParamMetaData =
nullptr;
22FactMetaData* SimpleMissionItem::_frameMetaData =
nullptr;
23FactMetaData* SimpleMissionItem::_latitudeMetaData =
nullptr;
24FactMetaData* SimpleMissionItem::_longitudeMetaData =
nullptr;
28 , _supportedCommandFact (0,
"Command:",
FactMetaData::valueTypeUint32)
29 , _altitudeFact (0,
"Altitude",
FactMetaData::valueTypeDouble)
30 , _amslAltAboveTerrainFact (0,
"Alt above terrain",
FactMetaData::valueTypeDouble)
39 _editorQml = QStringLiteral(
"qrc:/qml/QGroundControl/Controls/SimpleItemEditor.qml");
46 _updateOptionalSections();
47 _setDefaultsForCommand();
55 , _missionItem (missionItem)
56 , _supportedCommandFact (0,
"Command:",
FactMetaData::valueTypeUint32)
57 , _altitudeFact (0,
"Altitude",
FactMetaData::valueTypeDouble)
58 , _amslAltAboveTerrainFact (0,
"Alt above terrain",
FactMetaData::valueTypeDouble)
67 _editorQml = QStringLiteral(
"qrc:/qml/QGroundControl/Controls/SimpleItemEditor.qml");
69 struct MavFrame2AltMode_s {
74 const struct MavFrame2AltMode_s rgMavFrame2AltMode[] = {
80 for (
size_t i=0; i<
sizeof(rgMavFrame2AltMode)/
sizeof(rgMavFrame2AltMode[0]); i++) {
81 const MavFrame2AltMode_s& pMavFrame2AltMode = rgMavFrame2AltMode[i];
83 _altitudeMode = pMavFrame2AltMode.altMode;
89 _altitudeFact.setRawValue(
specifiesAltitude() ? _missionItem._param7Fact.rawValue() : qQNaN());
90 _amslAltAboveTerrainFact.setRawValue(qQNaN());
97 _updateOptionalSections();
108void SimpleMissionItem::_connectSignals(
void)
111 connect(&_missionItem._param1Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_setDirty);
112 connect(&_missionItem._param2Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_setDirty);
113 connect(&_missionItem._param3Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_setDirty);
114 connect(&_missionItem._param4Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_setDirty);
115 connect(&_missionItem._param5Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_setDirty);
116 connect(&_missionItem._param6Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_setDirty);
117 connect(&_missionItem._param7Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_setDirty);
118 connect(&_missionItem._frameFact, &
Fact::valueChanged,
this, &SimpleMissionItem::_setDirty);
119 connect(&_missionItem._commandFact, &
Fact::valueChanged,
this, &SimpleMissionItem::_setDirty);
123 connect(&_altitudeFact, &
Fact::valueChanged,
this, &SimpleMissionItem::_altitudeChanged);
139 connect(&_missionItem._param5Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_sendCoordinateChanged);
140 connect(&_missionItem._param6Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_sendCoordinateChanged);
142 connect(&_missionItem._param1Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_possibleAdditionalTimeDelayChanged);
143 connect(&_missionItem._param4Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_possibleVehicleYawChanged);
146 connect(&_missionItem._param2Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_possibleRadiusChanged);
147 connect(&_missionItem._param3Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_possibleRadiusChanged);
154 connect(&_missionItem._autoContinueFact, &
Fact::valueChanged,
this, &SimpleMissionItem::_sendFriendlyEditAllowedChanged);
155 connect(&_missionItem._commandFact, &
Fact::valueChanged,
this, &SimpleMissionItem::_sendFriendlyEditAllowedChanged);
156 connect(&_missionItem._frameFact, &
Fact::valueChanged,
this, &SimpleMissionItem::_sendFriendlyEditAllowedChanged);
159 connect(&_missionItem._commandFact, &
Fact::valueChanged,
this, &SimpleMissionItem::_setDefaultsForCommand);
177 connect(&_missionItem._param1Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_signalIfVTOLTransitionCommand);
180 connect(&_missionItem._commandFact, &
Fact::valueChanged,
this, &SimpleMissionItem::_sendCommandChanged);
190void SimpleMissionItem::_setupMetaData(
void)
192 QStringList enumStrings;
193 QVariantList enumValues;
195 if (!_altitudeMetaData) {
207 enumValues.append(QVariant((
int)
command));
210 _commandMetaData->
setEnumInfo(enumStrings, enumValues);
217 for (
size_t i=0; i<
sizeof(_rgMavFrameInfo)/
sizeof(_rgMavFrameInfo[0]); i++) {
218 const struct EnumInfo_s* mavFrameInfo = &_rgMavFrameInfo[i];
220 enumStrings.append(mavFrameInfo->label);
221 enumValues.append(QVariant(mavFrameInfo->frame));
224 _frameMetaData->
setEnumInfo(enumStrings, enumValues);
236 _missionItem._commandFact.setMetaData(_commandMetaData);
237 _missionItem._frameFact.setMetaData(_frameMetaData);
238 _altitudeFact.setMetaData(_altitudeMetaData);
239 _amslAltAboveTerrainFact.setMetaData(_altitudeMetaData);
248 QList<MissionItem*> items;
252 for (
int i=0; i<items.count(); i++) {
254 QJsonObject saveObject;
255 item->
save(saveObject);
259 saveObject[_jsonAltitudeModeKey] = _altitudeMode;
260 saveObject[_jsonAltitudeKey] = _altitudeFact.rawValue().toDouble();
261 saveObject[_jsonAMSLAltAboveTerrainKey] = _amslAltAboveTerrainFact.rawValue().toDouble();
264 missionItems.append(saveObject);
272 if ((success = _missionItem.
load(loadStream))) {
275 _altitudeFact.setRawValue(_missionItem._param7Fact.rawValue());
276 _amslAltAboveTerrainFact.setRawValue(qQNaN());
279 _updateOptionalSections();
294 if (json.contains(_jsonAltitudeModeKey) || json.contains(_jsonAltitudeKey) || json.contains(_jsonAMSLAltAboveTerrainKey)) {
295 QList<JsonHelper::KeyValidateInfo> keyInfoList = {
296 { _jsonAltitudeModeKey, QJsonValue::Double,
true },
297 { _jsonAltitudeKey, QJsonValue::Double,
true },
298 { _jsonAMSLAltAboveTerrainKey, QJsonValue::Null,
true },
309 _altitudeFact.setRawValue(_missionItem._param7Fact.rawValue());
310 _amslAltAboveTerrainFact.setRawValue(qQNaN());
315 _updateOptionalSections();
358 qWarning() <<
"Should not ask for command description on unknown command";
369 qWarning() <<
"Request for command name on unknown command";
370 return tr(
"Unknown: %1").arg(
command());
380 case MAV_CMD_NAV_TAKEOFF:
381 return tr(
"Takeoff");
382 case MAV_CMD_NAV_LAND:
384 case MAV_CMD_NAV_VTOL_TAKEOFF:
385 return tr(
"Transition Direction");
386 case MAV_CMD_NAV_VTOL_LAND:
387 return tr(
"VTOL Land");
388 case MAV_CMD_DO_SET_ROI:
389 case MAV_CMD_DO_SET_ROI_LOCATION:
391 case MAV_CMD_NAV_LOITER_TIME:
392 case MAV_CMD_NAV_LOITER_TURNS:
393 case MAV_CMD_NAV_LOITER_UNLIM:
394 case MAV_CMD_NAV_LOITER_TO_ALT:
401void SimpleMissionItem::_rebuildTextFieldFacts(
void)
403 _textFieldFacts.
clear();
404 _textFieldFactsAdvanced.
clear();
407 _missionItem._param1Fact.setName(
"Param1");
408 _missionItem._param1Fact.setMetaData(_defaultParamMetaData);
409 _textFieldFacts.
append(&_missionItem._param1Fact);
410 _missionItem._param2Fact.setName(
"Param2");
411 _missionItem._param2Fact.setMetaData(_defaultParamMetaData);
412 _textFieldFacts.
append(&_missionItem._param2Fact);
413 _missionItem._param3Fact.setName(
"Param3");
414 _missionItem._param3Fact.setMetaData(_defaultParamMetaData);
415 _textFieldFacts.
append(&_missionItem._param3Fact);
416 _missionItem._param4Fact.setName(
"Param4");
417 _missionItem._param4Fact.setMetaData(_defaultParamMetaData);
418 _textFieldFacts.
append(&_missionItem._param4Fact);
419 _missionItem._param5Fact.setName(
"Lat/X");
420 _missionItem._param5Fact.setMetaData(_defaultParamMetaData);
421 _textFieldFacts.
append(&_missionItem._param5Fact);
422 _missionItem._param6Fact.setName(
"Lon/Y");
423 _missionItem._param6Fact.setMetaData(_defaultParamMetaData);
424 _textFieldFacts.
append(&_missionItem._param6Fact);
425 _missionItem._param7Fact.setName(
"Alt/Z");
426 _missionItem._param7Fact.setMetaData(_defaultParamMetaData);
427 _textFieldFacts.
append(&_missionItem._param7Fact);
429 _ignoreDirtyChangeSignals =
true;
438 Fact* rgParamFacts[7] = { &_missionItem._param1Fact, &_missionItem._param2Fact, &_missionItem._param3Fact, &_missionItem._param4Fact, &_missionItem._param5Fact, &_missionItem._param6Fact, &_missionItem._param7Fact };
439 FactMetaData* rgParamMetaData[7] = { &_param1MetaData, &_param2MetaData, &_param3MetaData, &_param4MetaData, &_param5MetaData, &_param6MetaData, &_param7MetaData };
444 for (
int i=1; i<=7; i++) {
449 Fact* paramFact = rgParamFacts[i-1];
452 paramFact->setName(paramInfo->
label());
458 const double userMin = paramInfo->
userMin();
459 const double userMax = paramInfo->
userMax();
461 if (!qIsNaN(userMin)) {
464 if (!qIsNaN(userMax)) {
467 paramFact->setMetaData(paramMetaData);
469 _textFieldFactsAdvanced.
append(paramFact);
471 _textFieldFacts.
append(paramFact);
477 _ignoreDirtyChangeSignals =
false;
481void SimpleMissionItem::_rebuildNaNFacts(
void)
484 _nanFactsAdvanced.
clear();
487 _ignoreDirtyChangeSignals =
true;
496 Fact* rgParamFacts[7] = { &_missionItem._param1Fact, &_missionItem._param2Fact, &_missionItem._param3Fact, &_missionItem._param4Fact, &_missionItem._param5Fact, &_missionItem._param6Fact, &_missionItem._param7Fact };
497 FactMetaData* rgParamMetaData[7] = { &_param1MetaData, &_param2MetaData, &_param3MetaData, &_param4MetaData, &_param5MetaData, &_param6MetaData, &_param7MetaData };
502 for (
int i=1; i<=7; i++) {
509 Vehicle* firmwareVehicle = MultiVehicleManager::instance()->activeVehicle();
510 if (!firmwareVehicle) {
514 Fact* paramFact = rgParamFacts[i-1];
517 paramFact->setName(paramInfo->
label());
523 const double userMin = paramInfo->
userMin();
524 const double userMax = paramInfo->
userMax();
526 if (!qIsNaN(userMin)) {
529 if (!qIsNaN(userMax)) {
532 paramFact->setMetaData(paramMetaData);
534 _nanFactsAdvanced.
append(paramFact);
536 _nanFacts.
append(paramFact);
542 _ignoreDirtyChangeSignals =
false;
587void SimpleMissionItem::_rebuildComboBoxFacts(
void)
589 _comboboxFacts.
clear();
590 _comboboxFactsAdvanced.
clear();
593 _comboboxFacts.
append(&_missionItem._commandFact);
594 _comboboxFacts.
append(&_missionItem._frameFact);
596 _ignoreDirtyChangeSignals =
true;
598 Fact* rgParamFacts[7] = { &_missionItem._param1Fact, &_missionItem._param2Fact, &_missionItem._param3Fact, &_missionItem._param4Fact, &_missionItem._param5Fact, &_missionItem._param6Fact, &_missionItem._param7Fact };
599 FactMetaData* rgParamMetaData[7] = { &_param1MetaData, &_param2MetaData, &_param3MetaData, &_param4MetaData, &_param5MetaData, &_param6MetaData, &_param7MetaData };
608 for (
int i=1; i<=7; i++) {
612 if (showUI && paramInfo && paramInfo->
enumStrings().count() != 0) {
613 Fact* paramFact = rgParamFacts[i-1];
616 paramFact->setName(paramInfo->
label());
623 const double userMin = paramInfo->
userMin();
624 const double userMax = paramInfo->
userMax();
626 if (!qIsNaN(userMin)) {
629 if (!qIsNaN(userMax)) {
632 paramFact->setMetaData(paramMetaData);
634 _comboboxFactsAdvanced.
append(paramFact);
636 _comboboxFacts.
append(paramFact);
641 _ignoreDirtyChangeSignals =
false;
645void SimpleMissionItem::_rebuildFacts(
void)
647 _rebuildTextFieldFacts();
649 _rebuildComboBoxFacts();
661 MAV_FRAME frame = _missionItem.
frame();
663 case MAV_FRAME_GLOBAL:
664 case MAV_FRAME_GLOBAL_RELATIVE_ALT:
665 case MAV_FRAME_GLOBAL_TERRAIN_ALT:
685 if (this->
rawEdit() != rawEdit) {
703void SimpleMissionItem::_setDirty(
void)
705 if (!_ignoreDirtyChangeSignals) {
710void SimpleMissionItem::_sendCoordinateChanged(
void)
715void SimpleMissionItem::_altitudeModeChanged(
void)
717 switch (_altitudeMode) {
719 _missionItem.
setFrame(MAV_FRAME_GLOBAL_TERRAIN_ALT);
723 _missionItem.
setFrame(MAV_FRAME_GLOBAL);
725 _missionItem._param7Fact.setRawValue(qQNaN());
726 _amslAltAboveTerrainFact.setRawValue(qQNaN());
729 _missionItem.
setFrame(MAV_FRAME_GLOBAL);
732 _missionItem.
setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
735 qWarning() <<
"Internal Error SimpleMissionItem::_altitudeModeChanged: Invalid altitudeMode == AltitudeModeNone";
738 qWarning() <<
"Internal Error SimpleMissionItem::_altitudeModeChanged: Invalid altitudeMode == AltitudeModeMixed";
746void SimpleMissionItem::_altitudeChanged(
void)
753 _amslAltAboveTerrainFact.setRawValue(qQNaN());
754 _terrainAltChanged();
758 _missionItem._param7Fact.setRawValue(_altitudeFact.rawValue());
762void SimpleMissionItem::_terrainAltChanged(
void)
773 _missionItem._param7Fact.setRawValue(qQNaN());
775 _amslAltAboveTerrainFact.setRawValue(qQNaN());
777 double newAboveTerrain =
terrainAltitude() + _altitudeFact.rawValue().toDouble();
778 double oldAboveTerrain = _amslAltAboveTerrainFact.rawValue().toDouble();
781 _missionItem._param7Fact.setRawValue(newAboveTerrain);
783 _amslAltAboveTerrainFact.setRawValue(newAboveTerrain);
796 bool terrainReady = !
specifiesAltitude() || !qIsNaN(_missionItem._param7Fact.rawValue().toDouble());
800void SimpleMissionItem::_setDefaultsForCommand(
void)
803 _missionItem._param1Fact.setRawValue(0);
804 _missionItem._param2Fact.setRawValue(0);
805 _missionItem._param3Fact.setRawValue(0);
806 _missionItem._param4Fact.setRawValue(0);
810 _missionItem._param5Fact.setRawValue(0);
811 _missionItem._param6Fact.setRawValue(0);
814 _missionItem._param5Fact.setRawValue(_mapCenterHint.latitude());
815 _missionItem._param6Fact.setRawValue(_mapCenterHint.longitude());
821 _amslAltAboveTerrainFact.setRawValue(qQNaN());
824 _altitudeFact.setRawValue(defaultAlt);
825 _missionItem._param7Fact.setRawValue(defaultAlt);
830 _altitudeFact.setRawValue(0);
831 _missionItem._param7Fact.setRawValue(0);
832 _missionItem.
setFrame(MAV_FRAME_MISSION);
838 for (
int i=1; i<=7; i++) {
842 Fact* rgParamFacts[7] = { &_missionItem._param1Fact, &_missionItem._param2Fact, &_missionItem._param3Fact, &_missionItem._param4Fact, &_missionItem._param5Fact, &_missionItem._param6Fact, &_missionItem._param7Fact };
848 if (
command == MAV_CMD_NAV_WAYPOINT) {
853 _altitudeFact.setRawValue(0);
861void SimpleMissionItem::_sendCommandChanged(
void)
866void SimpleMissionItem::_sendFriendlyEditAllowedChanged(
void)
874 return uiInfo ? uiInfo->
category() : QString();
881 _updateOptionalSections();
889 if (command == MAV_CMD_NAV_LOITER_TO_ALT)
917 if (_speedSection->specifyFlightSpeed()) {
918 return _speedSection->
flightSpeed()->rawValue().toDouble();
939void SimpleMissionItem::_possibleVehicleYawChanged(
void)
941 if (
command() == MAV_CMD_NAV_WAYPOINT) {
948 bool sectionFound =
false;
951 sectionFound |= _cameraSection->
scanForSection(visualItems, scanIndex);
954 sectionFound |= _speedSection->
scanForSection(visualItems, scanIndex);
960void SimpleMissionItem::_updateOptionalSections(
void)
963 if (_cameraSection) {
964 _cameraSection->deleteLater();
965 _cameraSection =
nullptr;
968 _speedSection->deleteLater();
969 _speedSection =
nullptr;
976 if (
static_cast<MAV_CMD
>(
command()) == MAV_CMD_NAV_WAYPOINT) {
1002void SimpleMissionItem::_updateLastSequenceNumber(
void)
1007void SimpleMissionItem::_sectionDirtyChanged(
bool dirty)
1031 switch (
static_cast<MAV_CMD
>(this->
command())) {
1032 case MAV_CMD_NAV_LAND:
1033 case MAV_CMD_NAV_VTOL_LAND:
1037 _altitudeFact.setRawValue(newAltitude);
1051 if (_cameraSection->
available() && !_cameraSection->specifyGimbal()) {
1072 case MAV_CMD_NAV_WAYPOINT:
1073 case MAV_CMD_CONDITION_DELAY:
1074 case MAV_CMD_NAV_DELAY:
1081void SimpleMissionItem::_possibleAdditionalTimeDelayChanged(
void)
1084 case MAV_CMD_NAV_WAYPOINT:
1085 case MAV_CMD_CONDITION_DELAY:
1086 case MAV_CMD_NAV_DELAY:
1101 if (qIsNaN(_missionItem.
param5()) || qIsNaN(_missionItem.
param6())) {
1102 return QGeoCoordinate();
1104 return QGeoCoordinate(_missionItem.
param5(), _missionItem.
param6());
1110 return _missionItem.
param7();
1115 switch (_altitudeMode) {
1120 return _missionItem.
param7();
1124 qWarning() <<
"Internal Error SimpleMissionItem::amslEntryAlt: Invalid altitudeMode:AltitudeModeNone";
1127 qWarning() <<
"Internal Error SimpleMissionItem::amslEntryAlt: Invalid altitudeMode:AltitudeModeMixed";
1131 qWarning() <<
"Internal Error SimpleMissionItem::amslEntryAlt: Invalid altitudeMode:" << _altitudeMode;
1135void SimpleMissionItem::_signalIfVTOLTransitionCommand(
void)
1137 if (
mavCommand() == MAV_CMD_DO_VTOL_TRANSITION) {
1143void SimpleMissionItem::_possibleRadiusChanged(
void)
Fact *defaultMissionItemAltitude READ defaultMissionItemAltitude CONSTANT Fact * defaultMissionItemAltitude()
bool scanForSection(QmlObjectListModel *visualItems, int scanIndex) override
double specifiedGimbalPitch(void) const
void appendSectionItems(QList< MissionItem * > &items, QObject *missionItemParent, int &seqNum) override
void specifiedGimbalYawChanged(double gimbalYaw)
double specifiedGimbalYaw(void) const
void specifiedGimbalPitchChanged(double gimbalPitch)
bool available(void) const override
int itemCount(void) const override
void setDirty(bool dirty) override
void setAvailable(bool available) override
A Fact is used to hold a single value within the system.
void valueChanged(const QVariant &value)
This signal is only meant for use by the QT property system. It should not be connected to by client ...
bool advanced(void) const
QString label(void) const
QString units(void) const
QVariantList enumValues(void) const
QStringList enumStrings(void) const
double userMin(void) const
double defaultValue(void) const
double userMax(void) const
bool nanUnchanged(void) const
bool isLandCommand(MAV_CMD command) const
static MissionCommandTree * instance()
const MissionCommandUIInfo * getUIInfo(Vehicle *vehicle, QGCMAVLink::VehicleClass_t vtolMode, MAV_CMD command)
bool isLoiterCommand(void) const
QString category(void) const
QString description(void) const
QString friendlyName(void) const
bool specifiesCoordinate(void) const
const MissionCmdParamInfo * getParamInfo(int index, bool &showUI) const
bool isStandaloneCoordinate(void) const
bool specifiesAltitudeOnly(void) const
bool isLandCommand(void) const
bool friendlyEdit(void) const
void plannedHomePositionChanged(QGeoCoordinate plannedHomePosition)
QGeoCoordinate plannedHomePosition(void) const
double specifiedGimbalPitch(void) const
MAV_CMD command(void) const
double specifiedFlightSpeed(void) const
void specifiedFlightSpeedChanged(double flightSpeed)
void setFrame(MAV_FRAME frame)
double param5(void) const
void setParam7(double param7)
double specifiedGimbalYaw(void) const
void setAutoContinue(bool autoContinue)
bool relativeAltitude(void) const
void setParam6(double param6)
double param7(void) const
MAV_FRAME frame(void) const
void save(QJsonObject &json) const
void setParam3(double param3)
bool autoContinue(void) const
bool isCurrentItem(void) const
double param3(void) const
double param6(void) const
double param1(void) const
void setParam2(double param2)
int sequenceNumber(void) const
double param4(void) const
void setSequenceNumber(int sequenceNumber)
double param2(void) const
void sequenceNumberChanged(int sequenceNumber)
bool load(QTextStream &loadStream)
void setParam5(double param5)
void setCommand(MAV_CMD command)
Master controller for mission, fence, rally.
MissionController * missionController(void)
@ AltitudeModeCalcAboveTerrain
@ AltitudeModeTerrainFrame
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
void clear() override final
void dirtyChanged(bool dirty)
void itemCountChanged(int itemCount)
bool available READ available WRITE setAvailable NOTIFY availableChanged(bool settingsSpecified READ settingsSpecified NOTIFY settingsSpecifiedChanged) 1(bool dirty READ dirty WRITE setDirty NOTIFY availableChanged) virtual bool available(void) const =0
bool specifiesCoordinate(void) const final
void setSequenceNumber(int sequenceNumber) final
bool specifiesAltitudeOnly(void) const final
ReadyForSaveState readyForSaveState(void) const final
double editableAlt(void) const final
bool dirty(void) const override
bool friendlyEditAllowed(void) const
void rawEditChanged(bool rawEdit)
void speedSectionChanged(QObject *cameraSection)
bool isStandaloneCoordinate(void) const final
void applyNewAltitude(double newAltitude) final
Adjust the altitude of the item if appropriate to the new altitude.
void appendMissionItems(QList< MissionItem * > &items, QObject *missionItemParent) final
void isLoiterItemChanged(void)
SimpleMissionItem(PlanMasterController *masterController, bool flyView, bool forLoad)
void friendlyEditAllowedChanged(bool friendlyEditAllowed)
int sequenceNumber(void) const final
QGroundControlQmlGlobal::AltMode altitudeMode(void) const
void loiterRadiusChanged(double loiterRadius)
void showLoiterRadiusChanged(void)
bool scanForSections(QmlObjectListModel *visualItems, int scanIndex, PlanMasterController *masterController)
bool showLoiterRadius(void) const
QString abbreviation(void) const final
void altitudeModeChanged(void)
double specifiedVehicleYaw(void) override
int lastSequenceNumber(void) const final
void setRadius(double loiterRadius)
MAV_CMD mavCommand(void) const
double amslEntryAlt(void) const final
bool specifiesAltitude(void) const
bool isLandCommand(void) const final
QGeoCoordinate coordinate(void) const final
void setAltitudeMode(QGroundControlQmlGlobal::AltMode altitudeMode)
virtual bool load(QTextStream &loadStream)
QString commandDescription(void) const final
double loiterRadius(void) const
QString commandName(void) const final
void setCoordinate(const QGeoCoordinate &coordinate) override
void setCommand(int command)
double specifiedFlightSpeed(void) override
bool isLoiterItem(void) const
QString category READ category NOTIFY commandChanged(bool friendlyEditAllowed READ friendlyEditAllowed NOTIFY friendlyEditAllowedChanged) 1(bool rawEdit READ rawEdit WRITE setRawEdit NOTIFY rawEditChanged) 1(bool specifiesAltitude READ specifiesAltitude NOTIFY commandChanged) 1(Fact *altitude READ altitude CONSTANT) 1(QGroundControlQmlGlobal
< true: raw item editing with all params
double specifiedGimbalYaw(void) override
void setMissionFlightStatus(MissionController::MissionFlightStatus_t &missionFlightStatus) final
MissionItem & missionItem(void)
double specifiedGimbalPitch(void) override
void cameraSectionChanged(QObject *cameraSection)
void setDirty(bool dirty) final
void setRawEdit(bool rawEdit)
void save(QJsonArray &missionItems) final
QString category(void) const
double additionalTimeDelay(void) const final
void setAvailable(bool available) override
int itemCount(void) const override
void specifiedFlightSpeedChanged(double flightSpeed)
void appendSectionItems(QList< MissionItem * > &items, QObject *missionItemParent, int &seqNum) override
void setDirty(bool dirty) override
bool available(void) const override
bool scanForSection(QmlObjectListModel *visualItems, int scanIndex) override
void _amslExitAltChanged(void)
PlanMasterController * _masterController
void specifiedVehicleYawChanged(void)
bool _homePositionSpecialCase
true: This item is being used as a ui home position indicator
void abbreviationChanged(void)
virtual bool isTakeoffItem(void) const
void amslExitAltChanged(double alt)
QString _editorQml
Qml resource for editing item.
void terrainAltitudeChanged(double terrainAltitude)
void specifiesAltitudeOnlyChanged(void)
void lastSequenceNumberChanged(int sequenceNumber)
void commandNameChanged(void)
void entryCoordinateChanged(const QGeoCoordinate &entryCoordinate)
void specifiesCoordinateChanged(void)
void coordinateChanged(const QGeoCoordinate &coordinate)
void readyForSaveStateChanged(void)
void specifiedFlightSpeedChanged(void)
void currentVTOLModeChanged(void)
Signals that this item has changed the VTOL mode (MAV_CMD_DO_VTOL_TRANSITION)
void commandDescriptionChanged(void)
Vehicle * _controllerVehicle
MissionController * _missionController
void specifiedGimbalYawChanged(void)
void isStandaloneCoordinateChanged(void)
void amslEntryAltChanged(double alt)
void specifiedGimbalPitchChanged(void)
virtual void setMissionFlightStatus(MissionController::MissionFlightStatus_t &missionFlightStatus)
double _terrainAltitude
Altitude of terrain at coordinate position, NaN for not known.
bool _wizardMode
true: Item editor is showing wizard completion panel
void _amslEntryAltChanged(void)
void dirtyChanged(bool dirty)
void isLandCommandChanged(void)
void previousVTOLModeChanged(void)
void sequenceNumberChanged(int sequenceNumber)
QGCMAVLink::VehicleClass_t _previousVTOLMode
Generic == unknown.
void exitCoordinateChanged(const QGeoCoordinate &exitCoordinate)
void additionalTimeDelayChanged(void)
void wizardModeChanged(bool wizardMode)
double terrainAltitude(void) const
bool validateKeys(const QJsonObject &jsonObject, const QList< KeyValidateInfo > &keyInfo, QString &errorString)
double possibleNaNJsonValue(const QJsonValue &value)
Returns NaN if the value is null, or the value converted to double otherwise.
bool fuzzyCompare(double value1, double value2)
Returns true if the two values are equal or close. Correctly handles 0 and NaN values.
double vehicleSpeed
Either cruise or hover speed based on vehicle type and vtol state.
double gimbalPitch
NaN signals pitch was never changed.
double gimbalYaw
NaN signals yaw was never changed.