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