QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
SimpleMissionItem.cc
Go to the documentation of this file.
1#include "SimpleMissionItem.h"
2#include "JsonHelper.h"
3#include "JsonParsing.h"
7#include "SettingsManager.h"
8#include "AppSettings.h"
10#include "SpeedSection.h"
11#include "MultiVehicleManager.h"
12#include "CameraSection.h"
13#include "Vehicle.h"
14#include "QGC.h"
15
16#include <QtCore/QStringList>
17#include <QtCore/QJsonArray>
18
19FactMetaData* SimpleMissionItem::_altitudeMetaData = nullptr;
20FactMetaData* SimpleMissionItem::_commandMetaData = nullptr;
21FactMetaData* SimpleMissionItem::_defaultParamMetaData = nullptr;
22FactMetaData* SimpleMissionItem::_frameMetaData = nullptr;
23FactMetaData* SimpleMissionItem::_latitudeMetaData = nullptr;
24FactMetaData* SimpleMissionItem::_longitudeMetaData = nullptr;
25
26SimpleMissionItem::SimpleMissionItem(PlanMasterController* masterController, bool flyView, bool forLoad)
27 : VisualMissionItem (masterController, flyView)
28 , _supportedCommandFact (0, "Command:", FactMetaData::valueTypeUint32)
29 , _altitudeFact (0, "Altitude", FactMetaData::valueTypeDouble)
30 , _amslAltAboveTerrainFact (0, "Alt above terrain", FactMetaData::valueTypeDouble)
31 , _param1MetaData (FactMetaData::valueTypeDouble)
32 , _param2MetaData (FactMetaData::valueTypeDouble)
33 , _param3MetaData (FactMetaData::valueTypeDouble)
34 , _param4MetaData (FactMetaData::valueTypeDouble)
35 , _param5MetaData (FactMetaData::valueTypeDouble)
36 , _param6MetaData (FactMetaData::valueTypeDouble)
37 , _param7MetaData (FactMetaData::valueTypeDouble)
38{
39 _editorQml = QStringLiteral("qrc:/qml/QGroundControl/Controls/SimpleItemEditor.qml");
40
41 _setupMetaData();
42
43 if (!forLoad) {
44 // We are are going to load the SimpleItem right after this then don't connnect up signalling until after load is done
45 _connectSignals();
46 _updateOptionalSections();
47 _setDefaultsForCommand();
48 _rebuildFacts();
49 setDirty(false);
50 }
51}
52
53SimpleMissionItem::SimpleMissionItem(PlanMasterController* masterController, bool flyView, const MissionItem& missionItem)
54 : VisualMissionItem (masterController, flyView)
55 , _missionItem (missionItem)
56 , _supportedCommandFact (0, "Command:", FactMetaData::valueTypeUint32)
57 , _altitudeFact (0, "Altitude", FactMetaData::valueTypeDouble)
58 , _amslAltAboveTerrainFact (0, "Alt above terrain", FactMetaData::valueTypeDouble)
59 , _param1MetaData (FactMetaData::valueTypeDouble)
60 , _param2MetaData (FactMetaData::valueTypeDouble)
61 , _param3MetaData (FactMetaData::valueTypeDouble)
62 , _param4MetaData (FactMetaData::valueTypeDouble)
63 , _param5MetaData (FactMetaData::valueTypeDouble)
64 , _param6MetaData (FactMetaData::valueTypeDouble)
65 , _param7MetaData (FactMetaData::valueTypeDouble)
66{
67 _editorQml = QStringLiteral("qrc:/qml/QGroundControl/Controls/SimpleItemEditor.qml");
68
69 struct MavFrame2AltMode_s {
70 MAV_FRAME mavFrame;
72 };
73
74 const struct MavFrame2AltMode_s rgMavFrame2AltMode[] = {
75 { MAV_FRAME_GLOBAL_TERRAIN_ALT, QGroundControlQmlGlobal::AltitudeModeTerrainFrame },
77 { MAV_FRAME_GLOBAL_RELATIVE_ALT, QGroundControlQmlGlobal::AltitudeModeRelative },
78 };
80 for (size_t i=0; i<sizeof(rgMavFrame2AltMode)/sizeof(rgMavFrame2AltMode[0]); i++) {
81 const MavFrame2AltMode_s& pMavFrame2AltMode = rgMavFrame2AltMode[i];
82 if (pMavFrame2AltMode.mavFrame == missionItem.frame()) {
83 _altitudeMode = pMavFrame2AltMode.altMode;
84 break;
85 }
86 }
87
89 _altitudeFact.setRawValue(specifiesAltitude() ? _missionItem._param7Fact.rawValue() : qQNaN());
90 _amslAltAboveTerrainFact.setRawValue(qQNaN());
91
92 // In flyView we skip some of the intialization to save memory
93 if (!_flyView) {
94 _setupMetaData();
95 }
96 _connectSignals();
97 _updateOptionalSections();
98 if (!_flyView) {
99 _rebuildFacts();
100 }
101
102 // Signal coordinate changed to kick off terrain query
104
105 setDirty(false);
106}
107
108void SimpleMissionItem::_connectSignals(void)
109{
110 // Connect to change signals to track dirty state
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);
120 connect(&_missionItem, &MissionItem::sequenceNumberChanged, this, &SimpleMissionItem::_setDirty);
121 connect(this, &SimpleMissionItem::altitudeModeChanged, this, &SimpleMissionItem::_setDirty);
122
123 connect(&_altitudeFact, &Fact::valueChanged, this, &SimpleMissionItem::_altitudeChanged);
124 connect(this, &SimpleMissionItem::altitudeModeChanged, this, &SimpleMissionItem::_altitudeModeChanged);
125 connect(this, &SimpleMissionItem::terrainAltitudeChanged, this, &SimpleMissionItem::_terrainAltChanged);
126
128 connect(this, &SimpleMissionItem::cameraSectionChanged, this, &SimpleMissionItem::_setDirty);
129 connect(this, &SimpleMissionItem::cameraSectionChanged, this, &SimpleMissionItem::_updateLastSequenceNumber);
130
131 connect(&_missionItem._param7Fact, &Fact::valueChanged, this, &SimpleMissionItem::_amslEntryAltChanged);
135
137
138 // These are coordinate lat/lon values, they must emit coordinateChanged signal
139 connect(&_missionItem._param5Fact, &Fact::valueChanged, this, &SimpleMissionItem::_sendCoordinateChanged);
140 connect(&_missionItem._param6Fact, &Fact::valueChanged, this, &SimpleMissionItem::_sendCoordinateChanged);
141
142 connect(&_missionItem._param1Fact, &Fact::valueChanged, this, &SimpleMissionItem::_possibleAdditionalTimeDelayChanged);
143 connect(&_missionItem._param4Fact, &Fact::valueChanged, this, &SimpleMissionItem::_possibleVehicleYawChanged);
144
145 // For NAV_LOITER_X commands, they must emit a radiusChanged signal
146 connect(&_missionItem._param2Fact, &Fact::valueChanged, this, &SimpleMissionItem::_possibleRadiusChanged);
147 connect(&_missionItem._param3Fact, &Fact::valueChanged, this, &SimpleMissionItem::_possibleRadiusChanged);
148
149 // Exit coordinate is the same as entrance coordinate
152
153 // The following changes may also change friendlyEditAllowed
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);
157
158 // A command change triggers a number of other changes as well.
159 connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::_setDefaultsForCommand);
160 connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::commandNameChanged);
161 connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::commandDescriptionChanged);
162 connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::abbreviationChanged);
163 connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::specifiesCoordinateChanged);
164 connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::specifiesAltitudeOnlyChanged);
165 connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::isStandaloneCoordinateChanged);
166 connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::isLandCommandChanged);
167 connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::isLoiterItemChanged);
168 connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::showLoiterRadiusChanged);
169
170 // Whenever these properties change the ui model changes as well
171 connect(this, &SimpleMissionItem::commandChanged, this, &SimpleMissionItem::_rebuildFacts);
172 connect(this, &SimpleMissionItem::rawEditChanged, this, &SimpleMissionItem::_rebuildFacts);
173 connect(this, &SimpleMissionItem::previousVTOLModeChanged,this, &SimpleMissionItem::_rebuildFacts);
174
175 // The following changes must signal currentVTOLModeChanged to cause a MissionController recalc
176 connect(this, &SimpleMissionItem::commandChanged, this, &SimpleMissionItem::_signalIfVTOLTransitionCommand);
177 connect(&_missionItem._param1Fact, &Fact::valueChanged, this, &SimpleMissionItem::_signalIfVTOLTransitionCommand);
178
179 // These fact signals must alway signal out through SimpleMissionItem signals
180 connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::_sendCommandChanged);
181
182 // Propogate signals from MissionItem up to SimpleMissionItem
185
188}
189
190void SimpleMissionItem::_setupMetaData(void)
191{
192 QStringList enumStrings;
193 QVariantList enumValues;
194
195 if (!_altitudeMetaData) {
196 _altitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble);
197 _altitudeMetaData->setRawUnits("m");
198 _altitudeMetaData->setRawIncrement(1);
199 _altitudeMetaData->setDecimalPlaces(1);
200 _altitudeMetaData->setRawUserMin(0.0);
201 _altitudeMetaData->setRawUserMax(121.92); // 400 feet
202
203 enumStrings.clear();
204 enumValues.clear();
205 for (const MAV_CMD command: MissionCommandTree::instance()->allCommandIds()) {
206 enumStrings.append(MissionCommandTree::instance()->rawName(command));
207 enumValues.append(QVariant((int)command));
208 }
209 _commandMetaData = new FactMetaData(FactMetaData::valueTypeUint32);
210 _commandMetaData->setEnumInfo(enumStrings, enumValues);
211
212 _defaultParamMetaData = new FactMetaData(FactMetaData::valueTypeDouble);
213 _defaultParamMetaData->setDecimalPlaces(7);
214
215 enumStrings.clear();
216 enumValues.clear();
217 for (size_t i=0; i<sizeof(_rgMavFrameInfo)/sizeof(_rgMavFrameInfo[0]); i++) {
218 const struct EnumInfo_s* mavFrameInfo = &_rgMavFrameInfo[i];
219
220 enumStrings.append(mavFrameInfo->label);
221 enumValues.append(QVariant(mavFrameInfo->frame));
222 }
223 _frameMetaData = new FactMetaData(FactMetaData::valueTypeUint32);
224 _frameMetaData->setEnumInfo(enumStrings, enumValues);
225
226 _latitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble);
227 _latitudeMetaData->setRawUnits("deg");
228 _latitudeMetaData->setDecimalPlaces(7);
229
230 _longitudeMetaData = new FactMetaData(FactMetaData::valueTypeDouble);
231 _longitudeMetaData->setRawUnits("deg");
232 _longitudeMetaData->setDecimalPlaces(7);
233
234 }
235
236 _missionItem._commandFact.setMetaData(_commandMetaData);
237 _missionItem._frameFact.setMetaData(_frameMetaData);
238 _altitudeFact.setMetaData(_altitudeMetaData);
239 _amslAltAboveTerrainFact.setMetaData(_altitudeMetaData);
240}
241
245
246void SimpleMissionItem::save(QJsonArray& missionItems)
247{
248 QList<MissionItem*> items;
249
250 appendMissionItems(items, this);
251
252 for (int i=0; i<items.count(); i++) {
253 MissionItem* item = items[i];
254 QJsonObject saveObject;
255 item->save(saveObject);
256 if (i == 0) {
257 // This is the main simple item, save the alt/terrain data
258 if (specifiesAltitude()) {
259 saveObject[_jsonAltitudeModeKey] = _altitudeMode;
260 saveObject[_jsonAltitudeKey] = _altitudeFact.rawValue().toDouble();
261 saveObject[_jsonAMSLAltAboveTerrainKey] = _amslAltAboveTerrainFact.rawValue().toDouble();
262 }
263 }
264 missionItems.append(saveObject);
265 item->deleteLater();
266 }
267}
268
269bool SimpleMissionItem::load(QTextStream &loadStream)
270{
271 bool success;
272 if ((success = _missionItem.load(loadStream))) {
273 if (specifiesAltitude()) {
275 _altitudeFact.setRawValue(_missionItem._param7Fact.rawValue());
276 _amslAltAboveTerrainFact.setRawValue(qQNaN());
277 }
278 _connectSignals();
279 _updateOptionalSections();
280 _rebuildFacts();
281 setDirty(false);
282 }
283
284 return success;
285}
286
287bool SimpleMissionItem::load(const QJsonObject& json, int sequenceNumber, QString& errorString)
288{
289 if (!_missionItem.load(json, sequenceNumber, errorString)) {
290 return false;
291 }
292
293 if (specifiesAltitude()) {
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 },
299 };
300 if (!JsonHelper::validateKeys(json, keyInfoList, errorString)) {
301 return false;
302 }
303
304 _altitudeMode = (QGroundControlQmlGlobal::AltMode)(int)json[_jsonAltitudeModeKey].toDouble();
305 _altitudeFact.setRawValue(JsonParsing::possibleNaNJsonValue(json[_jsonAltitudeKey]));
306 _amslAltAboveTerrainFact.setRawValue(JsonParsing::possibleNaNJsonValue(json[_jsonAltitudeKey]));
307 } else {
309 _altitudeFact.setRawValue(_missionItem._param7Fact.rawValue());
310 _amslAltAboveTerrainFact.setRawValue(qQNaN());
311 }
312 }
313
314 _connectSignals();
315 _updateOptionalSections();
316 _rebuildFacts();
317 setDirty(false);
318
319 return true;
320}
321
323{
325 if (uiInfo) {
326 return uiInfo->isStandaloneCoordinate();
327 } else {
328 return false;
329 }
330}
331
333{
335 if (uiInfo) {
336 return uiInfo->specifiesCoordinate();
337 } else {
338 return false;
339 }
340}
341
343{
345 if (uiInfo) {
346 return uiInfo->specifiesAltitudeOnly();
347 } else {
348 return false;
349 }
350}
351
353{
355 if (uiInfo) {
356 return uiInfo->description();
357 } else {
358 qWarning() << "Should not ask for command description on unknown command";
359 return commandName();
360 }
361}
362
364{
366 if (uiInfo) {
367 return uiInfo->friendlyName();
368 } else {
369 qWarning() << "Request for command name on unknown command";
370 return tr("Unknown: %1").arg(command());
371 }
372}
373
375{
376 if (homePosition())
377 return tr("L");
378
379 switch(command()) {
380 case MAV_CMD_NAV_TAKEOFF:
381 return tr("Takeoff");
382 case MAV_CMD_NAV_LAND:
383 return tr("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:
390 return tr("ROI");
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:
395 return tr("Loiter");
396 default:
397 return QString();
398 }
399}
400
401void SimpleMissionItem::_rebuildTextFieldFacts(void)
402{
403 _textFieldFacts.clear();
404 _textFieldFactsAdvanced.clear();
405
406 if (rawEdit()) {
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);
428 } else {
429 _ignoreDirtyChangeSignals = true;
430
431 MAV_CMD command;
433 command = MAV_CMD_NAV_LAST;
434 } else {
435 command = _missionItem.command();
436 }
437
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 };
440
442
443 if (uiInfo) {
444 for (int i=1; i<=7; i++) {
445 bool showUI;
446 const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);
447
448 if (showUI && paramInfo && paramInfo->enumStrings().count() == 0 && !paramInfo->nanUnchanged()) {
449 Fact* paramFact = rgParamFacts[i-1];
450 FactMetaData* paramMetaData = rgParamMetaData[i-1];
451
452 paramFact->setName(paramInfo->label());
453 paramMetaData->setDecimalPlaces(paramInfo->decimalPlaces());
454 paramMetaData->setRawUnits(paramInfo->units());
455 paramMetaData->setRawDefaultValue(paramInfo->defaultValue());
456 paramMetaData->setRawMin(paramInfo->min());
457 paramMetaData->setRawMax(paramInfo->max());
458 const double userMin = paramInfo->userMin();
459 const double userMax = paramInfo->userMax();
460 // if user min/max are NaN, we leave them unchanged (invalid)
461 if (!qIsNaN(userMin)) {
462 paramMetaData->setRawUserMin(userMin);
463 }
464 if (!qIsNaN(userMax)) {
465 paramMetaData->setRawUserMax(userMax);
466 }
467 paramFact->setMetaData(paramMetaData);
468 if (paramInfo->advanced()) {
469 _textFieldFactsAdvanced.append(paramFact);
470 } else {
471 _textFieldFacts.append(paramFact);
472 }
473 }
474 }
475 }
476
477 _ignoreDirtyChangeSignals = false;
478 }
479}
480
481void SimpleMissionItem::_rebuildNaNFacts(void)
482{
483 _nanFacts.clear();
484 _nanFactsAdvanced.clear();
485
486 if (!rawEdit()) {
487 _ignoreDirtyChangeSignals = true;
488
489 MAV_CMD command;
491 command = MAV_CMD_NAV_LAST;
492 } else {
493 command = _missionItem.command();
494 }
495
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 };
498
500
501 if (uiInfo) {
502 for (int i=1; i<=7; i++) {
503 bool showUI;
504 const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);
505
506 if (showUI && paramInfo && paramInfo->nanUnchanged()) {
507 // Show hide Heading field on waypoint based on vehicle yaw to next waypoint setting. This needs to come from the actual vehicle if it exists
508 // and not _controllerVehicle which is always offline.
509 Vehicle* firmwareVehicle = MultiVehicleManager::instance()->activeVehicle();
510 if (!firmwareVehicle) {
511 firmwareVehicle = _controllerVehicle;
512 }
513
514 Fact* paramFact = rgParamFacts[i-1];
515 FactMetaData* paramMetaData = rgParamMetaData[i-1];
516
517 paramFact->setName(paramInfo->label());
518 paramMetaData->setDecimalPlaces(paramInfo->decimalPlaces());
519 paramMetaData->setRawUnits(paramInfo->units());
520 paramMetaData->setRawDefaultValue(paramInfo->defaultValue());
521 paramMetaData->setRawMin(paramInfo->min());
522 paramMetaData->setRawMax(paramInfo->max());
523 const double userMin = paramInfo->userMin();
524 const double userMax = paramInfo->userMax();
525 // if user min/max are NaN, we leave them unchanged (invalid)
526 if (!qIsNaN(userMin)) {
527 paramMetaData->setRawUserMin(userMin);
528 }
529 if (!qIsNaN(userMax)) {
530 paramMetaData->setRawUserMax(userMax);
531 }
532 paramFact->setMetaData(paramMetaData);
533 if (paramInfo->advanced()) {
534 _nanFactsAdvanced.append(paramFact);
535 } else {
536 _nanFacts.append(paramFact);
537 }
538 }
539 }
540 }
541
542 _ignoreDirtyChangeSignals = false;
543 }
544}
545
550
552{
554 if (uiInfo) {
555 return uiInfo->isLoiterCommand();
556 } else {
557 return false;
558 }
559}
560
562{
563 const MissionCommandUIInfo *uiInfo =
565 _controllerVehicle, _previousVTOLMode, MAV_CMD_NAV_LOITER_TIME);
566 bool showUI;
567 uiInfo->getParamInfo(3, showUI);
568
569 if (isLoiterItem() && command() == MAV_CMD_NAV_LOITER_TIME && !showUI) {
570 // Don't show the radius of MAV_CMD_NAV_LOITER_TIME items if the
571 // firmware doesn't support specifying it
572 return false;
573 }
574
576}
577
579{
580 if (isLoiterItem()) {
581 return command() == MAV_CMD_NAV_LOITER_TO_ALT ? missionItem().param2() : missionItem().param3();
582 } else {
583 return qQNaN();
584 }
585}
586
587void SimpleMissionItem::_rebuildComboBoxFacts(void)
588{
589 _comboboxFacts.clear();
590 _comboboxFactsAdvanced.clear();
591
592 if (rawEdit()) {
593 _comboboxFacts.append(&_missionItem._commandFact);
594 _comboboxFacts.append(&_missionItem._frameFact);
595 } else {
596 _ignoreDirtyChangeSignals = true;
597
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 };
600
601 MAV_CMD command;
603 command = MAV_CMD_NAV_LAST;
604 } else {
605 command = (MAV_CMD)this->command();
606 }
607
608 for (int i=1; i<=7; i++) {
609 bool showUI;
611
612 if (showUI && paramInfo && paramInfo->enumStrings().count() != 0) {
613 Fact* paramFact = rgParamFacts[i-1];
614 FactMetaData* paramMetaData = rgParamMetaData[i-1];
615
616 paramFact->setName(paramInfo->label());
617 paramMetaData->setDecimalPlaces(paramInfo->decimalPlaces());
618 paramMetaData->setEnumInfo(paramInfo->enumStrings(), paramInfo->enumValues());
619 paramMetaData->setRawUnits(paramInfo->units());
620 paramMetaData->setRawDefaultValue(paramInfo->defaultValue());
621 paramMetaData->setRawMin(paramInfo->min());
622 paramMetaData->setRawMax(paramInfo->max());
623 const double userMin = paramInfo->userMin();
624 const double userMax = paramInfo->userMax();
625 // if user min/max are NaN, we leave them unchanged (invalid)
626 if (!qIsNaN(userMin)) {
627 paramMetaData->setRawUserMin(userMin);
628 }
629 if (!qIsNaN(userMax)) {
630 paramMetaData->setRawUserMax(userMax);
631 }
632 paramFact->setMetaData(paramMetaData);
633 if (paramInfo->advanced()) {
634 _comboboxFactsAdvanced.append(paramFact);
635 } else {
636 _comboboxFacts.append(paramFact);
637 }
638 }
639 }
640
641 _ignoreDirtyChangeSignals = false;
642 }
643}
644
645void SimpleMissionItem::_rebuildFacts(void)
646{
647 _rebuildTextFieldFacts();
648 _rebuildNaNFacts();
649 _rebuildComboBoxFacts();
650}
651
653{
655 if (uiInfo && uiInfo->friendlyEdit()) {
656 if (!_missionItem.autoContinue()) {
657 return false;
658 }
659
660 if (specifiesAltitude()) {
661 MAV_FRAME frame = _missionItem.frame();
662 switch (frame) {
663 case MAV_FRAME_GLOBAL:
664 case MAV_FRAME_GLOBAL_RELATIVE_ALT:
665 case MAV_FRAME_GLOBAL_TERRAIN_ALT:
666 return true;
667 default:
668 return false;
669 }
670 }
671
672 return true;
673 }
674
675 return false;
676}
677
679{
680 return _rawEdit || !friendlyEditAllowed();
681}
682
684{
685 if (this->rawEdit() != rawEdit) {
686 _rawEdit = rawEdit;
687 emit rawEditChanged(this->rawEdit());
688 }
689}
690
692{
693 if (!_homePositionSpecialCase || (_dirty != dirty)) {
694 _dirty = dirty;
695 if (!dirty) {
696 _cameraSection->setDirty(false);
697 _speedSection->setDirty(false);
698 }
699 emit dirtyChanged(dirty);
700 }
701}
702
703void SimpleMissionItem::_setDirty(void)
704{
705 if (!_ignoreDirtyChangeSignals) {
706 setDirty(true);
707 }
708}
709
710void SimpleMissionItem::_sendCoordinateChanged(void)
711{
713}
714
715void SimpleMissionItem::_altitudeModeChanged(void)
716{
717 switch (_altitudeMode) {
719 _missionItem.setFrame(MAV_FRAME_GLOBAL_TERRAIN_ALT);
720 break;
722 // Terrain altitudes are Absolute
723 _missionItem.setFrame(MAV_FRAME_GLOBAL);
724 // Clear any old calculated values
725 _missionItem._param7Fact.setRawValue(qQNaN());
726 _amslAltAboveTerrainFact.setRawValue(qQNaN());
727 break;
729 _missionItem.setFrame(MAV_FRAME_GLOBAL);
730 break;
732 _missionItem.setFrame(MAV_FRAME_GLOBAL_RELATIVE_ALT);
733 break;
735 qWarning() << "Internal Error SimpleMissionItem::_altitudeModeChanged: Invalid altitudeMode == AltitudeModeNone";
736 break;
738 qWarning() << "Internal Error SimpleMissionItem::_altitudeModeChanged: Invalid altitudeMode == AltitudeModeMixed";
739 break;
740 }
741
742 // We always call _altitudeChanged to make sure that param7 is always setup correctly on mode change
743 _altitudeChanged();
744}
745
746void SimpleMissionItem::_altitudeChanged(void)
747{
748 if (!specifiesAltitude()) {
749 return;
750 }
751
753 _amslAltAboveTerrainFact.setRawValue(qQNaN());
754 _terrainAltChanged();
755 }
756
758 _missionItem._param7Fact.setRawValue(_altitudeFact.rawValue());
759 }
760}
761
762void SimpleMissionItem::_terrainAltChanged(void)
763{
764 if (!specifiesAltitude()) {
765 // We don't need terrain data
766 return;
767 }
768
770 if (qIsNaN(terrainAltitude())) {
771 // Set NaNs to signal we are waiting on terrain data
773 _missionItem._param7Fact.setRawValue(qQNaN());
774 }
775 _amslAltAboveTerrainFact.setRawValue(qQNaN());
776 } else {
777 double newAboveTerrain = terrainAltitude() + _altitudeFact.rawValue().toDouble();
778 double oldAboveTerrain = _amslAltAboveTerrainFact.rawValue().toDouble();
779 if (!QGC::fuzzyCompare(newAboveTerrain, oldAboveTerrain)) {
781 _missionItem._param7Fact.setRawValue(newAboveTerrain);
782 }
783 _amslAltAboveTerrainFact.setRawValue(newAboveTerrain);
784 }
785 }
787 }
788}
789
791{
792 if (_wizardMode) {
793 return NotReadyForSaveData;
794 }
795
796 bool terrainReady = !specifiesAltitude() || !qIsNaN(_missionItem._param7Fact.rawValue().toDouble());
797 return terrainReady ? ReadyForSave : NotReadyForSaveTerrain;
798}
799
800void SimpleMissionItem::_setDefaultsForCommand(void)
801{
802 // First reset params 1-4 to 0, we leave 5-7 alone to preserve any previous location information on command change
803 _missionItem._param1Fact.setRawValue(0);
804 _missionItem._param2Fact.setRawValue(0);
805 _missionItem._param3Fact.setRawValue(0);
806 _missionItem._param4Fact.setRawValue(0);
807
809 // No need to carry across previous lat/lon
810 _missionItem._param5Fact.setRawValue(0);
811 _missionItem._param6Fact.setRawValue(0);
812 } else if ((specifiesCoordinate() || isStandaloneCoordinate()) && _missionItem._param5Fact.rawValue().toDouble() == 0 && _missionItem._param6Fact.rawValue().toDouble() == 0) {
813 // We switched from a command without a coordinate to a command with a coordinate. Use the hint.
814 _missionItem._param5Fact.setRawValue(_mapCenterHint.latitude());
815 _missionItem._param6Fact.setRawValue(_mapCenterHint.longitude());
816 }
817
818 // Set global defaults first, then if there are param defaults they will get reset
820 emit altitudeModeChanged();
821 _amslAltAboveTerrainFact.setRawValue(qQNaN());
822 if (specifiesAltitude()) {
823 double defaultAlt = SettingsManager::instance()->appSettings()->defaultMissionItemAltitude()->rawValue().toDouble();
824 _altitudeFact.setRawValue(defaultAlt);
825 _missionItem._param7Fact.setRawValue(defaultAlt);
826 // Note that setAltitudeMode will also set MAV_FRAME correctly through signalling
827 // Takeoff items always use relative alt since that is the highest quality data to base altitude from
829 } else {
830 _altitudeFact.setRawValue(0);
831 _missionItem._param7Fact.setRawValue(0);
832 _missionItem.setFrame(MAV_FRAME_MISSION);
833 }
834
835 MAV_CMD command = static_cast<MAV_CMD>(this->command());
837 if (uiInfo) {
838 for (int i=1; i<=7; i++) {
839 bool showUI;
840 const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i, showUI);
841 if (paramInfo) {
842 Fact* rgParamFacts[7] = { &_missionItem._param1Fact, &_missionItem._param2Fact, &_missionItem._param3Fact, &_missionItem._param4Fact, &_missionItem._param5Fact, &_missionItem._param6Fact, &_missionItem._param7Fact };
843 rgParamFacts[paramInfo->param()-1]->setRawValue(paramInfo->defaultValue());
844 }
845 }
846 }
847
848 if (command == MAV_CMD_NAV_WAYPOINT) {
849 // We default all acceptance radius to 0. This allows flight controller to be in control of
850 // accept radius.
851 _missionItem.setParam2(0);
852 } else if ((uiInfo && uiInfo->isLandCommand()) || command == MAV_CMD_DO_SET_ROI_LOCATION) {
853 _altitudeFact.setRawValue(0);
854 _missionItem.setParam7(0);
855 }
856
857 _missionItem.setAutoContinue(true);
858 setRawEdit(false);
859}
860
861void SimpleMissionItem::_sendCommandChanged(void)
862{
863 emit commandChanged(command());
864}
865
866void SimpleMissionItem::_sendFriendlyEditAllowedChanged(void)
867{
869}
870
872{
874 return uiInfo ? uiInfo->category() : QString();
875}
876
878{
879 if (static_cast<MAV_CMD>(command) != _missionItem.command()) {
880 _missionItem.setCommand(static_cast<MAV_CMD>(command));
881 _updateOptionalSections();
882 }
883}
884
886{
887 if (isLoiterItem()) {
888 const MAV_CMD command = static_cast<MAV_CMD>(this->command());
889 if (command == MAV_CMD_NAV_LOITER_TO_ALT)
890 _missionItem.setParam2(radius);
891 else
892 _missionItem.setParam3(radius);
893 }
894}
895
896void SimpleMissionItem::setCoordinate(const QGeoCoordinate& coordinate)
897{
898 // We only use lat/lon from coordinate. This keeps param7 and the altitude value which is kept to the side in sync.
899 if (_missionItem.param5() != coordinate.latitude() || _missionItem.param6() != coordinate.longitude()) {
900 _missionItem.setParam5(coordinate.latitude());
901 _missionItem.setParam6(coordinate.longitude());
902 }
903}
904
906{
907 if (_missionItem.sequenceNumber() != sequenceNumber) {
908 _missionItem.setSequenceNumber(sequenceNumber);
910 // This is too likely to ignore
911 emit abbreviationChanged();
912 }
913}
914
916{
917 if (_speedSection->specifyFlightSpeed()) {
918 return _speedSection->flightSpeed()->rawValue().toDouble();
919 } else {
921 }
922}
923
925{
926 return _cameraSection->available() ? _cameraSection->specifiedGimbalYaw() : missionItem().specifiedGimbalYaw();
927}
928
930{
931 return _cameraSection->available() ? _cameraSection->specifiedGimbalPitch() : missionItem().specifiedGimbalPitch();
932}
933
935{
936 return command() == MAV_CMD_NAV_WAYPOINT ? missionItem().param4() : qQNaN();
937}
938
939void SimpleMissionItem::_possibleVehicleYawChanged(void)
940{
941 if (command() == MAV_CMD_NAV_WAYPOINT) {
943 }
944}
945
946bool SimpleMissionItem::scanForSections(QmlObjectListModel* visualItems, int scanIndex, PlanMasterController* /*masterController*/)
947{
948 bool sectionFound = false;
949
950 if (_cameraSection->available()) {
951 sectionFound |= _cameraSection->scanForSection(visualItems, scanIndex);
952 }
953 if (_speedSection->available()) {
954 sectionFound |= _speedSection->scanForSection(visualItems, scanIndex);
955 }
956
957 return sectionFound;
958}
959
960void SimpleMissionItem::_updateOptionalSections(void)
961{
962 // Remove previous sections
963 if (_cameraSection) {
964 _cameraSection->deleteLater();
965 _cameraSection = nullptr;
966 }
967 if (_speedSection) {
968 _speedSection->deleteLater();
969 _speedSection = nullptr;
970 }
971
972 // Add new sections
973
974 _cameraSection = new CameraSection(_masterController, this);
975 _speedSection = new SpeedSection(_masterController, this);
976 if (static_cast<MAV_CMD>(command()) == MAV_CMD_NAV_WAYPOINT) {
977 _cameraSection->setAvailable(true);
978 _speedSection->setAvailable(true);
979 }
980
981 connect(_cameraSection, &CameraSection::dirtyChanged, this, &SimpleMissionItem::_sectionDirtyChanged);
982 connect(_cameraSection, &CameraSection::itemCountChanged, this, &SimpleMissionItem::_updateLastSequenceNumber);
987
988 connect(_speedSection, &SpeedSection::dirtyChanged, this, &SimpleMissionItem::_sectionDirtyChanged);
989 connect(_speedSection, &SpeedSection::itemCountChanged, this, &SimpleMissionItem::_updateLastSequenceNumber);
991
992 emit cameraSectionChanged(_cameraSection);
993 emit speedSectionChanged(_speedSection);
995}
996
998{
999 return sequenceNumber() + (_cameraSection ? _cameraSection->itemCount() : 0) + (_speedSection ? _speedSection->itemCount() : 0);
1000}
1001
1002void SimpleMissionItem::_updateLastSequenceNumber(void)
1003{
1005}
1006
1007void SimpleMissionItem::_sectionDirtyChanged(bool dirty)
1008{
1009 if (dirty) {
1010 setDirty(true);
1011 }
1012}
1013
1014void SimpleMissionItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
1015{
1016 int seqNum = sequenceNumber();
1017
1018 items.append(new MissionItem(missionItem(), missionItemParent));
1019 seqNum++;
1020
1021 _cameraSection->appendSectionItems(items, missionItemParent, seqNum);
1022 _speedSection->appendSectionItems(items, missionItemParent, seqNum);
1023}
1024
1026{
1027 MAV_CMD command = static_cast<MAV_CMD>(this->command());
1029
1030 if (uiInfo && (uiInfo->specifiesCoordinate() || uiInfo->specifiesAltitudeOnly())) {
1031 switch (static_cast<MAV_CMD>(this->command())) {
1032 case MAV_CMD_NAV_LAND:
1033 case MAV_CMD_NAV_VTOL_LAND:
1034 // Leave alone
1035 break;
1036 default:
1037 _altitudeFact.setRawValue(newAltitude);
1038 break;
1039 }
1040 }
1041}
1042
1044{
1045 VisualMissionItem::setMissionFlightStatus(missionFlightStatus);
1046
1047 // If speed and/or gimbal are not specifically set on this item. Then use the flight status values as initial defaults should a user turn them on.
1048 if (_speedSection->available() && !_speedSection->specifyFlightSpeed() && !QGC::fuzzyCompare(_speedSection->flightSpeed()->rawValue().toDouble(), missionFlightStatus.vehicleSpeed)) {
1049 _speedSection->flightSpeed()->setRawValue(missionFlightStatus.vehicleSpeed);
1050 }
1051 if (_cameraSection->available() && !_cameraSection->specifyGimbal()) {
1052 if (!qIsNaN(missionFlightStatus.gimbalYaw) && !QGC::fuzzyCompare(_cameraSection->gimbalYaw()->rawValue().toDouble(), missionFlightStatus.gimbalYaw)) {
1053 _cameraSection->gimbalYaw()->setRawValue(missionFlightStatus.gimbalYaw);
1054 }
1055 if (!qIsNaN(missionFlightStatus.gimbalPitch) && !QGC::fuzzyCompare(_cameraSection->gimbalPitch()->rawValue().toDouble(), missionFlightStatus.gimbalPitch)) {
1056 _cameraSection->gimbalPitch()->setRawValue(missionFlightStatus.gimbalPitch);
1057 }
1058 }
1059}
1060
1062{
1063 if (altitudeMode != _altitudeMode) {
1064 _altitudeMode = altitudeMode;
1065 emit altitudeModeChanged();
1066 }
1067}
1068
1070{
1071 switch (command()) {
1072 case MAV_CMD_NAV_WAYPOINT:
1073 case MAV_CMD_CONDITION_DELAY:
1074 case MAV_CMD_NAV_DELAY:
1075 return missionItem().param1();
1076 default:
1077 return 0;
1078 }
1079}
1080
1081void SimpleMissionItem::_possibleAdditionalTimeDelayChanged(void)
1082{
1083 switch (command()) {
1084 case MAV_CMD_NAV_WAYPOINT:
1085 case MAV_CMD_CONDITION_DELAY:
1086 case MAV_CMD_NAV_DELAY:
1088 break;
1089 }
1090
1091 return;
1092}
1093
1095{
1096 return MissionCommandTree::instance()->isLandCommand(static_cast<MAV_CMD>(this->command()));
1097}
1098
1099QGeoCoordinate SimpleMissionItem::coordinate(void) const
1100{
1101 if (qIsNaN(_missionItem.param5()) || qIsNaN(_missionItem.param6())) {
1102 return QGeoCoordinate();
1103 } else {
1104 return QGeoCoordinate(_missionItem.param5(), _missionItem.param6());
1105 }
1106}
1107
1109{
1110 return _missionItem.param7();
1111}
1112
1114{
1115 switch (_altitudeMode) {
1117 return _missionItem.param7() + _terrainAltitude;
1120 return _missionItem.param7();
1122 return _missionItem.param7() + _masterController->missionController()->plannedHomePosition().altitude();
1124 qWarning() << "Internal Error SimpleMissionItem::amslEntryAlt: Invalid altitudeMode:AltitudeModeNone";
1125 return qQNaN();
1127 qWarning() << "Internal Error SimpleMissionItem::amslEntryAlt: Invalid altitudeMode:AltitudeModeMixed";
1128 return qQNaN();
1129 }
1130
1131 qWarning() << "Internal Error SimpleMissionItem::amslEntryAlt: Invalid altitudeMode:" << _altitudeMode;
1132 return qQNaN();
1133}
1134
1135void SimpleMissionItem::_signalIfVTOLTransitionCommand(void)
1136{
1137 if (mavCommand() == MAV_CMD_DO_VTOL_TRANSITION) {
1138 // This will cause a MissionController recalc
1140 }
1141}
1142
1143void SimpleMissionItem::_possibleRadiusChanged(void)
1144{
1145 if (isLoiterItem()) {
1147 }
1148}
QString errorString
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
Fact * gimbalPitch(void)
Fact * gimbalYaw(void)
void specifiedGimbalPitchChanged(double gimbalPitch)
bool available(void) const override
int itemCount(void) const override
void setDirty(bool dirty) override
void setAvailable(bool available) override
void setRawUnits(const QString &rawUnits)
void setDecimalPlaces(int decimalPlaces)
void setRawUserMin(const QVariant &rawUserMin)
void setRawUserMax(const QVariant &rawUserMax)
void setRawMin(const QVariant &rawMin)
void setRawDefaultValue(const QVariant &rawDefaultValue)
void setEnumInfo(const QStringList &strings, const QVariantList &values)
void setRawMax(const QVariant &rawMax)
void setRawIncrement(double increment)
A Fact is used to hold a single value within the system.
Definition Fact.h:19
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 max(void) const
double userMax(void) const
bool nanUnchanged(void) const
double min(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 friendlyEdit(void) const
void plannedHomePositionChanged(QGeoCoordinate plannedHomePosition)
QGeoCoordinate plannedHomePosition(void) const
double specifiedGimbalPitch(void) const
MAV_CMD command(void) const
Definition MissionItem.h:49
double specifiedFlightSpeed(void) const
void specifiedFlightSpeedChanged(double flightSpeed)
void setFrame(MAV_FRAME frame)
double param5(void) const
Definition MissionItem.h:58
void setParam7(double param7)
double specifiedGimbalYaw(void) const
void setAutoContinue(bool autoContinue)
bool relativeAltitude(void) const
Definition MissionItem.h:90
void setParam6(double param6)
double param7(void) const
Definition MissionItem.h:60
MAV_FRAME frame(void) const
Definition MissionItem.h:52
void save(QJsonObject &json) const
void setParam3(double param3)
bool autoContinue(void) const
Definition MissionItem.h:53
bool isCurrentItem(void) const
Definition MissionItem.h:50
double param3(void) const
Definition MissionItem.h:56
double param6(void) const
Definition MissionItem.h:59
double param1(void) const
Definition MissionItem.h:54
void setParam2(double param2)
int sequenceNumber(void) const
Definition MissionItem.h:51
double param4(void) const
Definition MissionItem.h:57
void setSequenceNumber(int sequenceNumber)
double param2(void) const
Definition MissionItem.h:55
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)
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 rawEdit(void) const
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
int command(void) const
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
Fact * flightSpeed(void)
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
bool vtol() const
Definition Vehicle.cc:1869
bool fixedWing() const
Definition Vehicle.cc:1844
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)
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.
Definition QGC.cc:106
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.