15#include <QtCore/QStringList>
16#include <QtCore/QJsonArray>
18FactMetaData* SimpleMissionItem::_altitudeMetaData =
nullptr;
19FactMetaData* SimpleMissionItem::_commandMetaData =
nullptr;
20FactMetaData* SimpleMissionItem::_defaultParamMetaData =
nullptr;
21FactMetaData* SimpleMissionItem::_frameMetaData =
nullptr;
22FactMetaData* SimpleMissionItem::_latitudeMetaData =
nullptr;
23FactMetaData* SimpleMissionItem::_longitudeMetaData =
nullptr;
27 , _supportedCommandFact (0,
"Command:",
FactMetaData::valueTypeUint32)
28 , _altitudeFact (0,
"Altitude",
FactMetaData::valueTypeDouble)
29 , _amslAltAboveTerrainFact (0,
"Alt above terrain",
FactMetaData::valueTypeDouble)
38 _editorQml = QStringLiteral(
"qrc:/qml/QGroundControl/PlanView/SimpleItemEditor.qml");
45 _updateOptionalSections();
46 _setDefaultsForCommand();
54 , _missionItem (missionItem)
55 , _supportedCommandFact (0,
"Command:",
FactMetaData::valueTypeUint32)
56 , _altitudeFact (0,
"Altitude",
FactMetaData::valueTypeDouble)
57 , _amslAltAboveTerrainFact (0,
"Alt above terrain",
FactMetaData::valueTypeDouble)
66 _editorQml = QStringLiteral(
"qrc:/qml/QGroundControl/PlanView/SimpleItemEditor.qml");
68 struct MavFrame2AltFrame_s {
73 const struct MavFrame2AltFrame_s rgMavFrame2AltFrame[] = {
79 for (
size_t i=0; i<
sizeof(rgMavFrame2AltFrame)/
sizeof(rgMavFrame2AltFrame[0]); i++) {
80 const MavFrame2AltFrame_s& pMavFrame2AltFrame = rgMavFrame2AltFrame[i];
82 _altitudeFrame = pMavFrame2AltFrame.altFrame;
96 _updateOptionalSections();
107void SimpleMissionItem::_connectSignals(
void)
110 connect(&_missionItem._param1Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_setDirty);
111 connect(&_missionItem._param2Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_setDirty);
112 connect(&_missionItem._param3Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_setDirty);
113 connect(&_missionItem._param4Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_setDirty);
114 connect(&_missionItem._param5Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_setDirty);
115 connect(&_missionItem._param6Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_setDirty);
116 connect(&_missionItem._param7Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_setDirty);
117 connect(&_missionItem._frameFact, &
Fact::valueChanged,
this, &SimpleMissionItem::_setDirty);
118 connect(&_missionItem._commandFact, &
Fact::valueChanged,
this, &SimpleMissionItem::_setDirty);
122 connect(&_altitudeFact, &
Fact::valueChanged,
this, &SimpleMissionItem::_altitudeChanged);
138 connect(&_missionItem._param5Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_sendCoordinateChanged);
139 connect(&_missionItem._param6Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_sendCoordinateChanged);
141 connect(&_missionItem._param1Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_possibleAdditionalTimeDelayChanged);
142 connect(&_missionItem._param4Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_possibleVehicleYawChanged);
145 connect(&_missionItem._param2Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_possibleRadiusChanged);
146 connect(&_missionItem._param3Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_possibleRadiusChanged);
153 connect(&_missionItem._autoContinueFact, &
Fact::valueChanged,
this, &SimpleMissionItem::_sendFriendlyEditAllowedChanged);
154 connect(&_missionItem._commandFact, &
Fact::valueChanged,
this, &SimpleMissionItem::_sendFriendlyEditAllowedChanged);
155 connect(&_missionItem._frameFact, &
Fact::valueChanged,
this, &SimpleMissionItem::_sendFriendlyEditAllowedChanged);
158 connect(&_missionItem._commandFact, &
Fact::valueChanged,
this, &SimpleMissionItem::_setDefaultsForCommand);
176 connect(&_missionItem._param1Fact, &
Fact::valueChanged,
this, &SimpleMissionItem::_signalIfVTOLTransitionCommand);
179 connect(&_missionItem._commandFact, &
Fact::valueChanged,
this, &SimpleMissionItem::_sendCommandChanged);
189void SimpleMissionItem::_setupMetaData(
void)
191 QStringList enumStrings;
192 QVariantList enumValues;
194 if (!_altitudeMetaData) {
206 enumValues.append(QVariant((
int)
command));
209 _commandMetaData->
setEnumInfo(enumStrings, enumValues);
216 for (
size_t i=0; i<
sizeof(_rgMavFrameInfo)/
sizeof(_rgMavFrameInfo[0]); i++) {
217 const struct EnumInfo_s* mavFrameInfo = &_rgMavFrameInfo[i];
219 enumStrings.append(mavFrameInfo->label);
220 enumValues.append(QVariant(mavFrameInfo->frame));
223 _frameMetaData->
setEnumInfo(enumStrings, enumValues);
235 _missionItem._commandFact.
setMetaData(_commandMetaData);
236 _missionItem._frameFact.
setMetaData(_frameMetaData);
238 _amslAltAboveTerrainFact.
setMetaData(_altitudeMetaData);
247 QList<MissionItem*> items;
251 for (
int i=0; i<items.count(); i++) {
253 QJsonObject saveObject;
254 item->
save(saveObject);
258 saveObject[_jsonAltitudeModeKey] = _altitudeFrame;
259 saveObject[_jsonAltitudeKey] = _altitudeFact.
rawValue().toDouble();
260 saveObject[_jsonAMSLAltAboveTerrainKey] = _amslAltAboveTerrainFact.
rawValue().toDouble();
263 missionItems.append(saveObject);
271 if ((success = _missionItem.
load(loadStream))) {
278 _updateOptionalSections();
293 if (json.contains(_jsonAltitudeModeKey) || json.contains(_jsonAltitudeKey) || json.contains(_jsonAMSLAltAboveTerrainKey)) {
294 QList<JsonParsing::KeyValidateInfo> keyInfoList = {
295 { _jsonAltitudeModeKey, QJsonValue::Double,
true },
296 { _jsonAltitudeKey, QJsonValue::Double,
true },
297 { _jsonAMSLAltAboveTerrainKey, QJsonValue::Null,
true },
314 _updateOptionalSections();
357 qWarning() <<
"Should not ask for command description on unknown command";
368 qWarning() <<
"Request for command name on unknown command";
369 return tr(
"Unknown: %1").arg(
command());
379 case MAV_CMD_NAV_TAKEOFF:
380 return tr(
"Takeoff");
381 case MAV_CMD_NAV_LAND:
383 case MAV_CMD_NAV_VTOL_TAKEOFF:
384 return tr(
"Transition Direction");
385 case MAV_CMD_NAV_VTOL_LAND:
386 return tr(
"VTOL Land");
387 case MAV_CMD_DO_SET_ROI:
388 case MAV_CMD_DO_SET_ROI_LOCATION:
390 case MAV_CMD_NAV_LOITER_TIME:
391 case MAV_CMD_NAV_LOITER_TURNS:
392 case MAV_CMD_NAV_LOITER_UNLIM:
393 case MAV_CMD_NAV_LOITER_TO_ALT:
400void SimpleMissionItem::_rebuildTextFieldFacts(
void)
402 _textFieldFacts.
clear();
403 _textFieldFactsAdvanced.
clear();
406 _missionItem._param1Fact.
setName(
"Param1");
407 _missionItem._param1Fact.
setMetaData(_defaultParamMetaData);
408 _textFieldFacts.
append(&_missionItem._param1Fact);
409 _missionItem._param2Fact.
setName(
"Param2");
410 _missionItem._param2Fact.
setMetaData(_defaultParamMetaData);
411 _textFieldFacts.
append(&_missionItem._param2Fact);
412 _missionItem._param3Fact.
setName(
"Param3");
413 _missionItem._param3Fact.
setMetaData(_defaultParamMetaData);
414 _textFieldFacts.
append(&_missionItem._param3Fact);
415 _missionItem._param4Fact.
setName(
"Param4");
416 _missionItem._param4Fact.
setMetaData(_defaultParamMetaData);
417 _textFieldFacts.
append(&_missionItem._param4Fact);
418 _missionItem._param5Fact.
setName(
"Lat/X");
419 _missionItem._param5Fact.
setMetaData(_defaultParamMetaData);
420 _textFieldFacts.
append(&_missionItem._param5Fact);
421 _missionItem._param6Fact.
setName(
"Lon/Y");
422 _missionItem._param6Fact.
setMetaData(_defaultParamMetaData);
423 _textFieldFacts.
append(&_missionItem._param6Fact);
424 _missionItem._param7Fact.
setName(
"Alt/Z");
425 _missionItem._param7Fact.
setMetaData(_defaultParamMetaData);
426 _textFieldFacts.
append(&_missionItem._param7Fact);
428 _ignoreDirtyChangeSignals =
true;
437 Fact* rgParamFacts[7] = { &_missionItem._param1Fact, &_missionItem._param2Fact, &_missionItem._param3Fact, &_missionItem._param4Fact, &_missionItem._param5Fact, &_missionItem._param6Fact, &_missionItem._param7Fact };
438 FactMetaData* rgParamMetaData[7] = { &_param1MetaData, &_param2MetaData, &_param3MetaData, &_param4MetaData, &_param5MetaData, &_param6MetaData, &_param7MetaData };
443 for (
int i=1; i<=7; i++) {
448 Fact* paramFact = rgParamFacts[i-1];
457 const double userMin = paramInfo->
userMin();
458 const double userMax = paramInfo->
userMax();
460 if (!qIsNaN(userMin)) {
463 if (!qIsNaN(userMax)) {
468 _textFieldFactsAdvanced.
append(paramFact);
470 _textFieldFacts.
append(paramFact);
476 _ignoreDirtyChangeSignals =
false;
480void SimpleMissionItem::_rebuildNaNFacts(
void)
483 _nanFactsAdvanced.
clear();
486 _ignoreDirtyChangeSignals =
true;
495 Fact* rgParamFacts[7] = { &_missionItem._param1Fact, &_missionItem._param2Fact, &_missionItem._param3Fact, &_missionItem._param4Fact, &_missionItem._param5Fact, &_missionItem._param6Fact, &_missionItem._param7Fact };
496 FactMetaData* rgParamMetaData[7] = { &_param1MetaData, &_param2MetaData, &_param3MetaData, &_param4MetaData, &_param5MetaData, &_param6MetaData, &_param7MetaData };
501 for (
int i=1; i<=7; i++) {
509 if (!firmwareVehicle) {
513 Fact* paramFact = rgParamFacts[i-1];
522 const double userMin = paramInfo->
userMin();
523 const double userMax = paramInfo->
userMax();
525 if (!qIsNaN(userMin)) {
528 if (!qIsNaN(userMax)) {
533 _nanFactsAdvanced.
append(paramFact);
535 _nanFacts.
append(paramFact);
541 _ignoreDirtyChangeSignals =
false;
586void SimpleMissionItem::_rebuildComboBoxFacts(
void)
588 _comboboxFacts.
clear();
589 _comboboxFactsAdvanced.
clear();
592 _comboboxFacts.
append(&_missionItem._commandFact);
593 _comboboxFacts.
append(&_missionItem._frameFact);
595 _ignoreDirtyChangeSignals =
true;
597 Fact* rgParamFacts[7] = { &_missionItem._param1Fact, &_missionItem._param2Fact, &_missionItem._param3Fact, &_missionItem._param4Fact, &_missionItem._param5Fact, &_missionItem._param6Fact, &_missionItem._param7Fact };
598 FactMetaData* rgParamMetaData[7] = { &_param1MetaData, &_param2MetaData, &_param3MetaData, &_param4MetaData, &_param5MetaData, &_param6MetaData, &_param7MetaData };
607 for (
int i=1; i<=7; i++) {
611 if (showUI && paramInfo && paramInfo->
enumStrings().count() != 0) {
612 Fact* paramFact = rgParamFacts[i-1];
622 const double userMin = paramInfo->
userMin();
623 const double userMax = paramInfo->
userMax();
625 if (!qIsNaN(userMin)) {
628 if (!qIsNaN(userMax)) {
633 _comboboxFactsAdvanced.
append(paramFact);
635 _comboboxFacts.
append(paramFact);
640 _ignoreDirtyChangeSignals =
false;
644void SimpleMissionItem::_rebuildFacts(
void)
646 _rebuildTextFieldFacts();
648 _rebuildComboBoxFacts();
660 MAV_FRAME frame = _missionItem.
frame();
662 case MAV_FRAME_GLOBAL:
663 case MAV_FRAME_GLOBAL_RELATIVE_ALT:
664 case MAV_FRAME_GLOBAL_TERRAIN_ALT:
684 if (this->
rawEdit() != rawEdit) {
702void SimpleMissionItem::_setDirty(
void)
704 if (!_ignoreDirtyChangeSignals) {
709void SimpleMissionItem::_sendCoordinateChanged(
void)
714void SimpleMissionItem::_altitudeFrameChanged(
void)
716 switch (_altitudeFrame) {
718 _missionItem.
setFrame(MAV_FRAME_GLOBAL_TERRAIN_ALT);
722 _missionItem.
setFrame(MAV_FRAME_GLOBAL);
728 _missionItem.
setFrame(MAV_FRAME_GLOBAL);
731 _missionItem.
setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
734 qWarning() <<
"Internal Error SimpleMissionItem::_altitudeFrameChanged: Invalid altitudeFrame == AltitudeFrameNone";
737 qWarning() <<
"Internal Error SimpleMissionItem::_altitudeFrameChanged: Invalid altitudeFrame == AltitudeFrameMixed";
745void SimpleMissionItem::_altitudeChanged(
void)
753 _terrainAltChanged();
761void SimpleMissionItem::_terrainAltChanged(
void)
777 double oldAboveTerrain = _amslAltAboveTerrainFact.
rawValue().toDouble();
780 _missionItem._param7Fact.
setRawValue(newAboveTerrain);
782 _amslAltAboveTerrainFact.
setRawValue(newAboveTerrain);
799void SimpleMissionItem::_setDefaultsForCommand(
void)
813 _missionItem._param5Fact.
setRawValue(_mapCenterHint.latitude());
814 _missionItem._param6Fact.
setRawValue(_mapCenterHint.longitude());
831 _missionItem.
setFrame(MAV_FRAME_MISSION);
837 for (
int i=1; i<=7; i++) {
841 Fact* rgParamFacts[7] = { &_missionItem._param1Fact, &_missionItem._param2Fact, &_missionItem._param3Fact, &_missionItem._param4Fact, &_missionItem._param5Fact, &_missionItem._param6Fact, &_missionItem._param7Fact };
847 if (
command == MAV_CMD_NAV_WAYPOINT) {
860void SimpleMissionItem::_sendCommandChanged(
void)
865void SimpleMissionItem::_sendFriendlyEditAllowedChanged(
void)
873 return uiInfo ? uiInfo->
category() : QString();
880 _updateOptionalSections();
888 if (command == MAV_CMD_NAV_LOITER_TO_ALT)
938void SimpleMissionItem::_possibleVehicleYawChanged(
void)
940 if (
command() == MAV_CMD_NAV_WAYPOINT) {
947 bool sectionFound =
false;
950 sectionFound |= _cameraSection->
scanForSection(visualItems, scanIndex);
953 sectionFound |= _speedSection->
scanForSection(visualItems, scanIndex);
959void SimpleMissionItem::_updateOptionalSections(
void)
962 if (_cameraSection) {
963 _cameraSection->deleteLater();
964 _cameraSection =
nullptr;
967 _speedSection->deleteLater();
968 _speedSection =
nullptr;
975 if (
static_cast<MAV_CMD
>(
command()) == MAV_CMD_NAV_WAYPOINT) {
1001void SimpleMissionItem::_updateLastSequenceNumber(
void)
1006void SimpleMissionItem::_sectionDirtyChanged(
bool dirty)
1030 switch (
static_cast<MAV_CMD
>(this->
command())) {
1031 case MAV_CMD_NAV_LAND:
1032 case MAV_CMD_NAV_VTOL_LAND:
1071 case MAV_CMD_NAV_WAYPOINT:
1072 case MAV_CMD_CONDITION_DELAY:
1073 case MAV_CMD_NAV_DELAY:
1080void SimpleMissionItem::_possibleAdditionalTimeDelayChanged(
void)
1083 case MAV_CMD_NAV_WAYPOINT:
1084 case MAV_CMD_CONDITION_DELAY:
1085 case MAV_CMD_NAV_DELAY:
1100 if (qIsNaN(_missionItem.
param5()) || qIsNaN(_missionItem.
param6())) {
1101 return QGeoCoordinate();
1103 return QGeoCoordinate(_missionItem.
param5(), _missionItem.
param6());
1109 return _missionItem.
param7();
1114 switch (_altitudeFrame) {
1119 return _missionItem.
param7();
1123 qWarning() <<
"Internal Error SimpleMissionItem::amslEntryAlt: Invalid altitudeFrame:AltitudeFrameNone";
1126 qWarning() <<
"Internal Error SimpleMissionItem::amslEntryAlt: Invalid altitudeFrame:AltitudeFrameMixed";
1130 qWarning() <<
"Internal Error SimpleMissionItem::amslEntryAlt: Invalid altitudeFrame:" << _altitudeFrame;
1134void SimpleMissionItem::_signalIfVTOLTransitionCommand(
void)
1136 if (
mavCommand() == MAV_CMD_DO_VTOL_TRANSITION) {
1142void SimpleMissionItem::_possibleRadiusChanged(
void)
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 specifyGimbal(void) const
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 setName(const QString &name)
Generally you should not change the name of a fact. But if you know what you are doing,...
void setMetaData(FactMetaData *metaData, bool setDefaultFromMetaData=false)
void setRawValue(const QVariant &value)
QVariant rawValue() const
Value after translation.
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 ...
UI Information associated with a mission command (MAV_CMD) parameter.
bool advanced(void) const
int decimalPlaces(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
Manages a hierarchy of MissionCommandUIInfo.
bool isLandCommand(MAV_CMD command) const
static MissionCommandTree * instance()
const MissionCommandUIInfo * getUIInfo(Vehicle *vehicle, QGCMAVLink::VehicleClass_t vtolMode, MAV_CMD command)
UI Information associated with a mission command (MAV_CMD)
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)
static MultiVehicleManager * instance()
Vehicle * activeVehicle() const
Master controller for mission, fence, rally.
MissionController * missionController(void)
@ AltitudeFrameCalcAboveTerrain
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
void clear() override final
void dirtyChanged(bool dirty)
void itemCountChanged(int itemCount)
void availableChanged(bool available)
static SettingsManager * instance()
AppSettings * appSettings() const
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)
void commandChanged(int command)
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
void loiterRadiusChanged(double loiterRadius)
void showLoiterRadiusChanged(void)
bool scanForSections(QmlObjectListModel *visualItems, int scanIndex, PlanMasterController *masterController)
bool showLoiterRadius(void) const
void altitudeFrameChanged(void)
QString abbreviation(void) const final
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
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
void setAltitudeFrame(QGroundControlQmlGlobal::AltitudeFrame altitudeFrame)
double specifiedGimbalYaw(void) override
MissionItem & missionItem(void)
~SimpleMissionItem()
true: raw item editing with all params
double specifiedGimbalPitch(void) override
void cameraSectionChanged(QObject *cameraSection)
QGroundControlQmlGlobal::AltitudeFrame altitudeFrame(void) const
void setDirty(bool dirty) final
void setRawEdit(bool rawEdit)
void save(QJsonArray &missionItems) final
QString category(void) const
void setMissionFlightStatus(MissionFlightStatus_t &missionFlightStatus) final
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
bool specifyFlightSpeed(void) const
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)
QGCMAVLinkTypes::VehicleClass_t _previousVTOLMode
Generic == unknown.
void readyForSaveStateChanged(void)
void specifiedFlightSpeedChanged(void)
void currentVTOLModeChanged(void)
Signals that this item has changed the VTOL mode (MAV_CMD_DO_VTOL_TRANSITION)
bool homePosition(void) const
< Flight path cumalative horizontal distance from home point to this item
void commandDescriptionChanged(void)
Vehicle * _controllerVehicle
MissionController * _missionController
void specifiedGimbalYawChanged(void)
void isStandaloneCoordinateChanged(void)
void amslEntryAltChanged(double alt)
void specifiedGimbalPitchChanged(void)
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)
void exitCoordinateChanged(const QGeoCoordinate &exitCoordinate)
void additionalTimeDelayChanged(void)
void wizardModeChanged(bool wizardMode)
virtual void setMissionFlightStatus(MissionFlightStatus_t &missionFlightStatus)
double terrainAltitude(void) const
bool validateKeys(const QJsonObject &jsonObject, const QList< KeyValidateInfo > &keyInfo, QString &errorString)
Validates that all required keys are present and that listed keys have the expected type.
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 gimbalPitch
NaN signals pitch was never changed.
double vehicleSpeed
Either cruise or hover speed based on vehicle type and vtol state.
double gimbalYaw
NaN signals yaw was never changed.