QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MissionController.cc
Go to the documentation of this file.
1#include "MissionController.h"
2#include "Vehicle.h"
3#include "VehicleSupports.h"
4#include "MissionManager.h"
5#include "FlightPathSegment.h"
6#include "FirmwarePlugin.h"
7#include "QGCApplication.h"
8#include "SimpleMissionItem.h"
9#include "SurveyComplexItem.h"
14#include "JsonHelper.h"
16#include "SettingsManager.h"
17#include "AppSettings.h"
18#include "MissionSettingsItem.h"
20#include "KMLPlanDomDocument.h"
21#include "QGCCorePlugin.h"
22#include "TakeoffMissionItem.h"
23#include "PlanViewSettings.h"
24#include "MissionCommandTree.h"
25#include "QGC.h"
26#include "QGCLoggingCategory.h"
27
28#include <QtCore/QJsonArray>
29#include <QtCore/QJsonDocument>
30#include <QtMath>
31
32#define UPDATE_TIMEOUT 5000
33
34QGC_LOGGING_CATEGORY(MissionControllerLog, "PlanManager.MissionController")
35
36MissionController::MissionController(PlanMasterController* masterController, QObject *parent)
37 : PlanElementController (masterController, parent)
38 , _controllerVehicle (masterController->controllerVehicle())
39 , _managerVehicle (masterController->managerVehicle())
40 , _missionManager (masterController->managerVehicle()->missionManager())
41 , _visualItems (new QmlObjectListModel(this))
42 , _planViewSettings (SettingsManager::instance()->planViewSettings())
43 , _appSettings (SettingsManager::instance()->appSettings())
44{
45 _resetMissionFlightStatus();
46
47 _updateTimer.setSingleShot(true);
48
49 connect(&_updateTimer, &QTimer::timeout, this, &MissionController::_updateTimeout);
50 connect(_planViewSettings->takeoffItemNotRequired(), &Fact::rawValueChanged, this, &MissionController::_forceRecalcOfAllowedBits);
51 connect(_planViewSettings->allowMultipleLandingPatterns(), &Fact::rawValueChanged, this, &MissionController::multipleLandPatternsAllowedChanged);
53 connect(this, &MissionController::multipleLandPatternsAllowedChanged, this, &MissionController::_forceRecalcOfAllowedBits);
55
56 // The follow is used to compress multiple recalc calls in a row to into a single call.
57 connect(this, &MissionController::_recalcMissionFlightStatusSignal, this, &MissionController::_recalcMissionFlightStatus, Qt::QueuedConnection);
58 connect(this, &MissionController::_recalcFlightPathSegmentsSignal, this, &MissionController::_recalcFlightPathSegments, Qt::QueuedConnection);
59 qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(&MissionController::_recalcMissionFlightStatusSignal));
60 qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(&MissionController::_recalcFlightPathSegmentsSignal));
61 qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(&MissionController::recalcTerrainProfile));
62}
63
68
69void MissionController::_resetMissionFlightStatus(void)
70{
71 _missionFlightStatus.totalDistance = 0.0;
72 _missionFlightStatus.plannedDistance = 0.0;
73 _missionFlightStatus.maxTelemetryDistance = 0.0;
74 _missionFlightStatus.totalTime = 0.0;
75 _missionFlightStatus.hoverTime = 0.0;
76 _missionFlightStatus.cruiseTime = 0.0;
77 _missionFlightStatus.hoverDistance = 0.0;
78 _missionFlightStatus.cruiseDistance = 0.0;
79 _missionFlightStatus.cruiseSpeed = _controllerVehicle->defaultCruiseSpeed();
80 _missionFlightStatus.hoverSpeed = _controllerVehicle->defaultHoverSpeed();
81 _missionFlightStatus.vehicleSpeed = _controllerVehicle->multiRotor() || _managerVehicle->vtol() ? _missionFlightStatus.hoverSpeed : _missionFlightStatus.cruiseSpeed;
82 _missionFlightStatus.vehicleYaw = qQNaN();
83 _missionFlightStatus.gimbalYaw = qQNaN();
84 _missionFlightStatus.gimbalPitch = qQNaN();
85 _missionFlightStatus.mAhBattery = 0;
86 _missionFlightStatus.hoverAmps = 0;
87 _missionFlightStatus.cruiseAmps = 0;
88 _missionFlightStatus.ampMinutesAvailable = 0;
89 _missionFlightStatus.hoverAmpsTotal = 0;
90 _missionFlightStatus.cruiseAmpsTotal = 0;
91 _missionFlightStatus.batteryChangePoint = -1;
92 _missionFlightStatus.batteriesRequired = -1;
93 _missionFlightStatus.vtolMode = _missionContainsVTOLTakeoff ? QGCMAVLink::VehicleClassMultiRotor : QGCMAVLink::VehicleClassFixedWing;
94
95 _controllerVehicle->firmwarePlugin()->batteryConsumptionData(_controllerVehicle, _missionFlightStatus.mAhBattery, _missionFlightStatus.hoverAmps, _missionFlightStatus.cruiseAmps);
96 if (_missionFlightStatus.mAhBattery != 0) {
97 double batteryPercentRemainingAnnounce = SettingsManager::instance()->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toDouble();
98 _missionFlightStatus.ampMinutesAvailable = static_cast<double>(_missionFlightStatus.mAhBattery) / 1000.0 * 60.0 * ((100.0 - batteryPercentRemainingAnnounce) / 100.0);
99 }
100
101 emit missionPlannedDistanceChanged(_missionFlightStatus.plannedDistance);
102 emit missionTimeChanged();
103 emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
104 emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
107 emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
108 emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
109 emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
110
111}
112
113void MissionController::start(bool flyView)
114{
115 qCDebug(MissionControllerLog) << "start flyView" << flyView;
116
117 _managerVehicleChanged(_managerVehicle);
118 connect(_masterController, &PlanMasterController::managerVehicleChanged, this, &MissionController::_managerVehicleChanged);
119
121 _init();
122}
123
124void MissionController::_init(void)
125{
126 // We start with an empty mission
127 _addMissionSettings(_visualItems);
128
129 // Set up the tree model structure once (groups + static children)
130 _setupTreeModel();
131
132 _initAllVisualItems();
133}
134
135// Called when new mission items have completed downloading from Vehicle
136void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllRequested)
137{
138 qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle flyView:count" << _flyView << _missionManager->missionItems().count();
139
140 // Fly view always reloads on _loadComplete
141 // Plan view only reloads if:
142 // - Load was specifically requested
143 // - There is no current Plan
144 if (_flyView || removeAllRequested || _itemsRequested || isEmpty()) {
145 // Fly Mode (accept if):
146 // - Always accepts new items from the vehicle so Fly view is kept up to date
147 // Edit Mode (accept if):
148 // - Remove all was requested from Fly view (clear mission on flight end)
149 // - A load from vehicle was manually requested
150 // - The initial automatic load from a vehicle completed and the current editor is empty
151
152 _deinitAllVisualItems();
153 _visualItems->clearAndDeleteContents();
154 _visualItems->deleteLater();
155 _visualItems = nullptr;
156 _settingsItem = nullptr;
157 _takeoffMissionItem = nullptr;
158 _updateContainsItems(); // This will clear containsItems which will be set again below. This will re-pop Start Mission confirmation.
159
160 QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
161 const QList<MissionItem*>& newMissionItems = _missionManager->missionItems();
162 qCDebug(MissionControllerLog) << "loading from vehicle: count"<< newMissionItems.count();
163
164 _missionItemCount = newMissionItems.count();
165 emit missionItemCountChanged(_missionItemCount);
166
167 MissionSettingsItem* settingsItem = _addMissionSettings(newControllerMissionItems);
168
169 int i=0;
170 if (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() && newMissionItems.count() != 0) {
171 // First item is fake home position
172 MissionItem* fakeHomeItem = newMissionItems[0];
173 if (fakeHomeItem->coordinate().latitude() != 0 || fakeHomeItem->coordinate().longitude() != 0) {
174 settingsItem->setInitialHomePosition(fakeHomeItem->coordinate());
175 }
176 i = 1;
177 }
178
179 bool weHaveItemsFromVehicle = false;
180 for (; i < newMissionItems.count(); i++) {
181 weHaveItemsFromVehicle = true;
182 const MissionItem* missionItem = newMissionItems[i];
183 SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, _flyView, *missionItem);
184 if (TakeoffMissionItem::isTakeoffCommand(static_cast<MAV_CMD>(simpleItem->command()))) {
185 // This needs to be a TakeoffMissionItem
186 _takeoffMissionItem = new TakeoffMissionItem(*missionItem, _masterController, _flyView, settingsItem, false /* forLoad */);
187 _takeoffMissionItem->setWizardMode(false);
188 simpleItem->deleteLater();
189 simpleItem = _takeoffMissionItem;
190 }
191 newControllerMissionItems->append(simpleItem);
192 }
193
194 _visualItems = newControllerMissionItems;
195 _settingsItem = settingsItem;
196
197 // We set Altitude mode to mixed, otherwise if we need a non relative altitude frame we won't be able to change it
198 setGlobalAltitudeMode(weHaveItemsFromVehicle ? QGroundControlQmlGlobal::AltitudeModeMixed : QGroundControlQmlGlobal::AltitudeModeRelative);
199
200 MissionController::_scanForAdditionalSettings(_visualItems, _masterController);
201
202 _initAllVisualItems();
203 _updateContainsItems();
204 emit newItemsFromVehicle();
205 }
206 _itemsRequested = false;
207}
208
210{
211 if (_masterController->offline()) {
212 qCCritical(MissionControllerLog) << "MissionControllerLog::loadFromVehicle called while offline";
213 } else if (syncInProgress()) {
214 qCCritical(MissionControllerLog) << "MissionControllerLog::loadFromVehicle called while syncInProgress";
215 } else {
216 _itemsRequested = true;
217 _managerVehicle->missionManager()->loadFromVehicle();
218 }
219}
220
222{
223 if (_masterController->offline()) {
224 qCCritical(MissionControllerLog) << "MissionControllerLog::sendToVehicle called while offline";
225 } else if (syncInProgress()) {
226 qCCritical(MissionControllerLog) << "MissionControllerLog::sendToVehicle called while syncInProgress";
227 } else {
228 qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
229 if (_visualItems->count() == 1) {
230 // This prevents us from sending a possibly bogus home position to the vehicle
231 QmlObjectListModel emptyModel;
232 sendItemsToVehicle(_managerVehicle, &emptyModel);
233 } else {
234 sendItemsToVehicle(_managerVehicle, _visualItems);
235 }
236 setDirty(false);
237 }
238}
239
243bool MissionController::_convertToMissionItems(QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent)
244{
245 if (visualMissionItems->count() == 0) {
246 return false;
247 }
248
249 bool endActionSet = false;
250 int lastSeqNum = 0;
251
252 for (int i=0; i<visualMissionItems->count(); i++) {
253 VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(visualMissionItems->get(i));
254
255 lastSeqNum = visualItem->lastSequenceNumber();
256 visualItem->appendMissionItems(rgMissionItems, missionItemParent);
257
258 qCDebug(MissionControllerLog) << "_convertToMissionItems seqNum:lastSeqNum:command"
259 << visualItem->sequenceNumber()
260 << lastSeqNum
261 << visualItem->commandName();
262 }
263
264 // Mission settings has a special case for end mission action
265 MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
266 if (settingsItem) {
267 endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
268 }
269
270 return endActionSet;
271}
272
274{
275 QObject* deleteParent = new QObject();
276 QList<MissionItem*> rgMissionItems;
277
278 _convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
279 planKML.addMission(_controllerVehicle, _visualItems, rgMissionItems);
280 deleteParent->deleteLater();
281}
282
284{
285 if (vehicle) {
286 QList<MissionItem*> rgMissionItems;
287
288 _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
289
290 // PlanManager takes control of MissionItems so no need to delete
291 vehicle->missionManager()->writeMissionItems(rgMissionItems);
292 }
293}
294
295int MissionController::_nextSequenceNumber(void)
296{
297 if (_visualItems->count() == 0) {
298 qWarning() << "Internal error: Empty visual item list";
299 return 0;
300 } else {
301 VisualMissionItem* lastItem = _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1);
302 return lastItem->lastSequenceNumber() + 1;
303 }
304}
305
306VisualMissionItem* MissionController::_insertSimpleMissionItemWorker(QGeoCoordinate coordinate, MAV_CMD command, int visualItemIndex, bool makeCurrentItem)
307{
308 int sequenceNumber = _nextSequenceNumber();
309 SimpleMissionItem * newItem = new SimpleMissionItem(_masterController, _flyView, false /* forLoad */);
310 newItem->setSequenceNumber(sequenceNumber);
311 newItem->setCoordinate(coordinate);
312 newItem->setCommand(command);
313 _initVisualItem(newItem);
314
315 if (newItem->specifiesAltitude()) {
316 if (!MissionCommandTree::instance()->isLandCommand(command)) {
317 double prevAltitude;
319
320 if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltMode)) {
321 newItem->altitude()->setRawValue(prevAltitude);
323 // We are in mixed altitude modes, so copy from previous. Otherwise alt mode will be set from global setting.
324 newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltMode>(prevAltMode));
325 }
326 }
327 }
328 }
329 if (visualItemIndex == -1) {
330 _visualItems->append(newItem);
331 } else {
332 _visualItems->insert(visualItemIndex, newItem);
333 }
334
335 // We send the click coordinate through here to be able to set the planned home position from the user click location if needed
336 _recalcAllWithCoordinate(coordinate);
337
338 if (makeCurrentItem) {
340 }
341
342 _firstItemAdded();
343
344 return newItem;
345}
346
347
348VisualMissionItem* MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem)
349{
350 return _insertSimpleMissionItemWorker(coordinate, MAV_CMD_NAV_WAYPOINT, visualItemIndex, makeCurrentItem);
351}
352
353VisualMissionItem* MissionController::insertTakeoffItem(QGeoCoordinate /*coordinate*/, int visualItemIndex, bool makeCurrentItem)
354{
355 int sequenceNumber = _nextSequenceNumber();
356 _takeoffMissionItem = new TakeoffMissionItem(_controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF, _masterController, _flyView, _settingsItem, false /* forLoad */);
357 _takeoffMissionItem->setSequenceNumber(sequenceNumber);
358 _initVisualItem(_takeoffMissionItem);
359
360 if (_takeoffMissionItem->specifiesAltitude()) {
361 double prevAltitude;
363
364 if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltMode)) {
365 _takeoffMissionItem->altitude()->setRawValue(prevAltitude);
366 _takeoffMissionItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltMode>(prevAltMode));
367 }
368 }
369 if (visualItemIndex == -1) {
370 _visualItems->append(_takeoffMissionItem);
371 } else {
372 _visualItems->insert(visualItemIndex, _takeoffMissionItem);
373 }
374
375 _recalcAll();
376
377 if (makeCurrentItem) {
378 setCurrentPlanViewSeqNum(_takeoffMissionItem->sequenceNumber(), true);
379 }
380
381 _firstItemAdded();
382
383 return _takeoffMissionItem;
384}
385
387 // Can't have more than one land sequence unless allowed in settings and
388 // supported by the firmware
389 return _planViewSettings->allowMultipleLandingPatterns()
390 ->rawValue().toBool() &&
392}
393
394VisualMissionItem* MissionController::insertLandItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem)
395{
396 if (_controllerVehicle->fixedWing()) {
397 FixedWingLandingComplexItem* fwLanding = qobject_cast<FixedWingLandingComplexItem*>(insertComplexMissionItem(FixedWingLandingComplexItem::name, coordinate, visualItemIndex, makeCurrentItem));
398 return fwLanding;
399 } else if (_controllerVehicle->vtol()) {
400 VTOLLandingComplexItem* vtolLanding = qobject_cast<VTOLLandingComplexItem*>(insertComplexMissionItem(VTOLLandingComplexItem::name, coordinate, visualItemIndex, makeCurrentItem));
401 return vtolLanding;
402 } else {
403 return _insertSimpleMissionItemWorker(coordinate, _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_RETURN_TO_LAUNCH, visualItemIndex, makeCurrentItem);
404 }
405}
406
407VisualMissionItem* MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem)
408{
409 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_insertSimpleMissionItemWorker(coordinate, MAV_CMD_DO_SET_ROI_LOCATION, visualItemIndex, makeCurrentItem));
410
411 if (!_controllerVehicle->firmwarePlugin()->supportedMissionCommands(QGCMAVLink::VehicleClassGeneric).contains(MAV_CMD_DO_SET_ROI_LOCATION)) {
412 simpleItem->setCommand(MAV_CMD_DO_SET_ROI) ;
413 simpleItem->missionItem().setParam1(MAV_ROI_LOCATION);
414 }
415 _recalcROISpecialVisuals();
416 return simpleItem;
417}
418
419VisualMissionItem* MissionController::insertCancelROIMissionItem(int visualItemIndex, bool makeCurrentItem)
420{
421 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_insertSimpleMissionItemWorker(QGeoCoordinate(), MAV_CMD_DO_SET_ROI_NONE, visualItemIndex, makeCurrentItem));
422
423 if (!_controllerVehicle->firmwarePlugin()->supportedMissionCommands(QGCMAVLink::VehicleClassGeneric).contains(MAV_CMD_DO_SET_ROI_NONE)) {
424 simpleItem->setCommand(MAV_CMD_DO_SET_ROI) ;
425 simpleItem->missionItem().setParam1(MAV_ROI_NONE);
426 }
427 _recalcROISpecialVisuals();
428 return simpleItem;
429}
430
431VisualMissionItem* MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int visualItemIndex, bool makeCurrentItem)
432{
433 ComplexMissionItem* newItem = nullptr;
434
435 if (itemName == SurveyComplexItem::name) {
436 newItem = new SurveyComplexItem(_masterController, _flyView, QString() /* kmlOrShpFile */);
437 newItem->setCoordinate(mapCenterCoordinate);
438
439 double prevAltitude;
442 // We are in mixed altitude modes, so copy from previous. Otherwise alt mode will be set from global setting in constructor.
443 if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltMode)) {
444 qobject_cast<SurveyComplexItem*>(newItem)->cameraCalc()->setDistanceMode(prevAltMode);
445 }
446 }
447 } else if (itemName == FixedWingLandingComplexItem::name) {
449 } else if (itemName == VTOLLandingComplexItem::name) {
451 } else if (itemName == StructureScanComplexItem::name) {
452 newItem = new StructureScanComplexItem(_masterController, _flyView, QString() /* kmlOrShpFile */);
453 } else if (itemName == CorridorScanComplexItem::name) {
454 newItem = new CorridorScanComplexItem(_masterController, _flyView, QString() /* kmlOrShpFile */);
455 } else {
456 qWarning() << "Internal error: Unknown complex item:" << itemName;
457 return nullptr;
458 }
459
460 _insertComplexMissionItemWorker(mapCenterCoordinate, newItem, visualItemIndex, makeCurrentItem);
461
462 return newItem;
463}
464
465VisualMissionItem* MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int visualItemIndex, bool makeCurrentItem)
466{
467 ComplexMissionItem* newItem = nullptr;
468
469 if (itemName == SurveyComplexItem::name) {
470 newItem = new SurveyComplexItem(_masterController, _flyView, file);
471 } else if (itemName == StructureScanComplexItem::name) {
473 } else if (itemName == CorridorScanComplexItem::name) {
475 } else {
476 qWarning() << "Internal error: Unknown complex item:" << itemName;
477 return nullptr;
478 }
479
480 _insertComplexMissionItemWorker(QGeoCoordinate(), newItem, visualItemIndex, makeCurrentItem);
481
482 return newItem;
483}
484
485void MissionController::_insertComplexMissionItemWorker(const QGeoCoordinate& mapCenterCoordinate, ComplexMissionItem* complexItem, int visualItemIndex, bool makeCurrentItem)
486{
487 int sequenceNumber = _nextSequenceNumber();
488 bool surveyStyleItem = qobject_cast<SurveyComplexItem*>(complexItem) ||
489 qobject_cast<CorridorScanComplexItem*>(complexItem) ||
490 qobject_cast<StructureScanComplexItem*>(complexItem);
491
492 if (surveyStyleItem) {
493 bool rollSupported = false;
494 bool pitchSupported = false;
495 bool yawSupported = false;
496
497 // If the vehicle is known to have a gimbal then we automatically point the gimbal straight down if not already set
498
499 MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
500 CameraSection* cameraSection = settingsItem->cameraSection();
501
502 // Set camera to photo mode (leave alone if user already specified)
503 if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
504 cameraSection->setSpecifyCameraMode(true);
505 cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
506 }
507
508 // Point gimbal straight down
509 if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
510 // If the user already specified a gimbal angle leave it alone
511 if (!cameraSection->specifyGimbal()) {
512 cameraSection->setSpecifyGimbal(true);
513 cameraSection->gimbalPitch()->setRawValue(-90.0);
514 }
515 }
516 }
517
518 complexItem->setSequenceNumber(sequenceNumber);
519 if (!qobject_cast<VTOLLandingComplexItem*>(complexItem)) {
520 complexItem->setWizardMode(true);
521 }
522 _initVisualItem(complexItem);
523
524 if (visualItemIndex == -1) {
525 _visualItems->append(complexItem);
526 } else {
527 _visualItems->insert(visualItemIndex, complexItem);
528 }
529
530 //-- Keep track of bounding box changes in complex items
531 if(!complexItem->isSimpleItem()) {
532 connect(complexItem, &ComplexMissionItem::boundingCubeChanged, this, &MissionController::_complexBoundingBoxChanged);
533 }
534 _recalcAllWithCoordinate(mapCenterCoordinate);
535
536 if (makeCurrentItem) {
537 setCurrentPlanViewSeqNum(complexItem->sequenceNumber(), true);
538 }
539 _firstItemAdded();
540}
541
542int MissionController::visualItemIndexForObject(QObject* object) const
543{
544 return _visualItems ? _visualItems->indexOf(object) : -1;
545}
546
547void MissionController::removeVisualItem(int viIndex)
548{
549 if (viIndex <= 0 || viIndex >= _visualItems->count()) {
550 qWarning() << "MissionController::removeVisualItem called with bad index - count:index" << _visualItems->count() << viIndex;
551 return;
552 }
553
554 bool removeSurveyStyle = _visualItems->value<SurveyComplexItem*>(viIndex) || _visualItems->value<CorridorScanComplexItem*>(viIndex);
555 VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(viIndex));
556
557 if (item == _takeoffMissionItem) {
558 _takeoffMissionItem = nullptr;
559 }
560
561 _deinitVisualItem(item);
562 item->deleteLater();
563
564 if (removeSurveyStyle) {
565 // Determine if the mission still has another survey style item in it
566 bool foundSurvey = false;
567 for (int i=1; i<_visualItems->count(); i++) {
568 if (_visualItems->value<SurveyComplexItem*>(i) || _visualItems->value<CorridorScanComplexItem*>(i)) {
569 foundSurvey = true;
570 break;
571 }
572 }
573
574 // If there is no longer a survey item in the mission remove added commands
575 if (!foundSurvey) {
576 bool rollSupported = false;
577 bool pitchSupported = false;
578 bool yawSupported = false;
579 CameraSection* cameraSection = _settingsItem->cameraSection();
580 if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
581 if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
582 cameraSection->setSpecifyGimbal(false);
583 }
584 }
585 if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
586 cameraSection->setSpecifyCameraMode(false);
587 }
588 }
589 }
590
591 _recalcAll();
592
593 // Adjust current item
594 int newVIIndex;
595 if (viIndex >= _visualItems->count()) {
596 newVIIndex = _visualItems->count() - 1;
597 } else {
598 newVIIndex = viIndex;
599 }
600 setCurrentPlanViewSeqNum(_visualItems->value<VisualMissionItem*>(newVIIndex)->sequenceNumber(), true);
601
602 setDirty(true);
603
604 if (_visualItems->count() == 1) {
605 _allItemsRemoved();
606 }
607}
608
610{
611 if (_visualItems) {
612 _deinitAllVisualItems();
613 _visualItems->clearAndDeleteContents();
614 _visualItems->deleteLater();
615 _settingsItem = nullptr;
616 _takeoffMissionItem = nullptr;
617 _visualItems = new QmlObjectListModel(this);
618 _addMissionSettings(_visualItems);
619 _initAllVisualItems();
620 setDirty(true);
621 _resetMissionFlightStatus();
622 _allItemsRemoved();
623 }
624}
625
626bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
627{
628 // Validate root object keys
629 QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
630 { _jsonPlannedHomePositionKey, QJsonValue::Object, true },
631 { _jsonItemsKey, QJsonValue::Array, true },
632 { _jsonMavAutopilotKey, QJsonValue::Double, false },
633 { _jsonComplexItemsKey, QJsonValue::Array, true },
634 };
635 if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
636 return false;
637 }
638
640
641 // Read complex items
642 QList<SurveyComplexItem*> surveyItems;
643 QJsonArray complexArray(json[_jsonComplexItemsKey].toArray());
644 qCDebug(MissionControllerLog) << "Json load: complex item count" << complexArray.count();
645 for (int i=0; i<complexArray.count(); i++) {
646 const QJsonValue& itemValue = complexArray[i];
647
648 if (!itemValue.isObject()) {
649 errorString = QStringLiteral("Mission item is not an object");
650 return false;
651 }
652
653 SurveyComplexItem* item = new SurveyComplexItem(_masterController, _flyView, QString() /* kmlOrShpFile */);
654 const QJsonObject itemObject = itemValue.toObject();
655 if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
656 surveyItems.append(item);
657 } else {
658 return false;
659 }
660 }
661
662 // Read simple items, interspersing complex items into the full list
663
664 int nextSimpleItemIndex= 0;
665 int nextComplexItemIndex= 0;
666 int nextSequenceNumber = 1; // Start with 1 since home is in 0
667 QJsonArray itemArray(json[_jsonItemsKey].toArray());
668
669 MissionSettingsItem* settingsItem = _addMissionSettings(visualItems);
670 if (json.contains(_jsonPlannedHomePositionKey)) {
671 SimpleMissionItem* item = new SimpleMissionItem(_masterController, _flyView, true /* forLoad */);
672 if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
673 settingsItem->setInitialHomePositionFromUser(item->coordinate());
674 item->deleteLater();
675 } else {
676 return false;
677 }
678 }
679
680 qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
681 do {
682 qCDebug(MissionControllerLog) << "Json load: simple item loop nextSimpleItemIndex:nextComplexItemIndex:nextSequenceNumber" << nextSimpleItemIndex << nextComplexItemIndex << nextSequenceNumber;
683
684 // If there is a complex item that should be next in sequence add it in
685 if (nextComplexItemIndex < surveyItems.count()) {
686 SurveyComplexItem* complexItem = surveyItems[nextComplexItemIndex];
687
688 if (complexItem->sequenceNumber() == nextSequenceNumber) {
689 qCDebug(MissionControllerLog) << "Json load: injecting complex item expectedSequence:actualSequence:" << nextSequenceNumber << complexItem->sequenceNumber();
690 visualItems->append(complexItem);
691 nextSequenceNumber = complexItem->lastSequenceNumber() + 1;
692 nextComplexItemIndex++;
693 continue;
694 }
695 }
696
697 // Add the next available simple item
698 if (nextSimpleItemIndex < itemArray.count()) {
699 const QJsonValue& itemValue = itemArray[nextSimpleItemIndex++];
700
701 if (!itemValue.isObject()) {
702 errorString = QStringLiteral("Mission item is not an object");
703 return false;
704 }
705
706 const QJsonObject itemObject = itemValue.toObject();
707 SimpleMissionItem* item = new SimpleMissionItem(_masterController, _flyView, true /* forLoad */);
708 if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
710 // This needs to be a TakeoffMissionItem
711 TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_masterController, _flyView, settingsItem, true /* forLoad */);
712 takeoffItem->load(itemObject, itemObject["id"].toInt(), errorString);
713 item->deleteLater();
714 item = takeoffItem;
715 }
716 qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
717 nextSequenceNumber = item->lastSequenceNumber() + 1;
718 visualItems->append(item);
719 } else {
720 return false;
721 }
722 }
723 } while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
724
725 return true;
726}
727
728bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
729{
730 // Validate root object keys
731 QList<JsonHelper::KeyValidateInfo> rootKeyInfoList = {
732 { _jsonPlannedHomePositionKey, QJsonValue::Array, true },
733 { _jsonItemsKey, QJsonValue::Array, true },
734 { _jsonFirmwareTypeKey, QJsonValue::Double, true },
735 { _jsonVehicleTypeKey, QJsonValue::Double, false },
736 { _jsonCruiseSpeedKey, QJsonValue::Double, false },
737 { _jsonHoverSpeedKey, QJsonValue::Double, false },
738 { _jsonGlobalPlanAltitudeModeKey, QJsonValue::Double, false },
739 };
740 if (!JsonHelper::validateKeys(json, rootKeyInfoList, errorString)) {
741 return false;
742 }
743
745
746 qCDebug(MissionControllerLog) << "MissionController::_loadJsonMissionFileV2 itemCount:" << json[_jsonItemsKey].toArray().count();
747
748 AppSettings* appSettings = SettingsManager::instance()->appSettings();
749
750 // Get the firmware/vehicle type from the plan file
751 MAV_AUTOPILOT planFileFirmwareType = static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt());
752 MAV_TYPE planFileVehicleType = static_cast<MAV_TYPE> (QGCMAVLink::vehicleClassToMavType(appSettings->offlineEditingVehicleClass()->rawValue().toInt()));
753 if (json.contains(_jsonVehicleTypeKey)) {
754 planFileVehicleType = static_cast<MAV_TYPE>(json[_jsonVehicleTypeKey].toInt());
755 }
756
757 // Update firmware/vehicle offline settings if we aren't connect to a vehicle
758 if (_masterController->offline()) {
759 appSettings->offlineEditingFirmwareClass()->setRawValue(QGCMAVLink::firmwareClass(static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt())));
760 if (json.contains(_jsonVehicleTypeKey)) {
761 appSettings->offlineEditingVehicleClass()->setRawValue(QGCMAVLink::vehicleClass(planFileVehicleType));
762 }
763 }
764
765 // The controller vehicle always tracks the Plan file firmware/vehicle types so update it
766 _controllerVehicle->stopTrackingFirmwareVehicleTypeChanges();
767 _controllerVehicle->_offlineFirmwareTypeSettingChanged(planFileFirmwareType);
768 _controllerVehicle->_offlineVehicleTypeSettingChanged(planFileVehicleType);
769
770 if (json.contains(_jsonCruiseSpeedKey)) {
771 appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
772 }
773 if (json.contains(_jsonHoverSpeedKey)) {
774 appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
775 }
776 if (json.contains(_jsonGlobalPlanAltitudeModeKey)) {
777 setGlobalAltitudeMode(json[_jsonGlobalPlanAltitudeModeKey].toVariant().value<QGroundControlQmlGlobal::AltMode>());
778 }
779
780 QGeoCoordinate homeCoordinate;
781 if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
782 return false;
783 }
785 settingsItem->setCoordinate(homeCoordinate);
786 visualItems->insert(0, settingsItem);
787 qCDebug(MissionControllerLog) << "plannedHomePosition" << homeCoordinate;
788
789 // Read mission items
790
791 int nextSequenceNumber = 1; // Start with 1 since home is in 0
792 const QJsonArray rgMissionItems(json[_jsonItemsKey].toArray());
793 for (int i=0; i<rgMissionItems.count(); i++) {
794 // Convert to QJsonObject
795 const QJsonValue& itemValue = rgMissionItems[i];
796 if (!itemValue.isObject()) {
797 errorString = tr("Mission item %1 is not an object").arg(i);
798 return false;
799 }
800 const QJsonObject itemObject = itemValue.toObject();
801
802 // Load item based on type
803
804 QList<JsonHelper::KeyValidateInfo> itemKeyInfoList = {
805 { VisualMissionItem::jsonTypeKey, QJsonValue::String, true },
806 };
807 if (!JsonHelper::validateKeys(itemObject, itemKeyInfoList, errorString)) {
808 return false;
809 }
810 QString itemType = itemObject[VisualMissionItem::jsonTypeKey].toString();
811
813 SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, _flyView, true /* forLoad */);
814 if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
815 if (TakeoffMissionItem::isTakeoffCommand(static_cast<MAV_CMD>(simpleItem->command()))) {
816 // This needs to be a TakeoffMissionItem
817 TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_masterController, _flyView, settingsItem, true /* forLoad */);
818 takeoffItem->load(itemObject, nextSequenceNumber, errorString);
819 simpleItem->deleteLater();
820 simpleItem = takeoffItem;
821 }
822 qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
823 nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
824 visualItems->append(simpleItem);
825 } else {
826 return false;
827 }
828 } else if (itemType == VisualMissionItem::jsonTypeComplexItemValue) {
829 QList<JsonHelper::KeyValidateInfo> complexItemKeyInfoList = {
830 { ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true },
831 };
832 if (!JsonHelper::validateKeys(itemObject, complexItemKeyInfoList, errorString)) {
833 return false;
834 }
835 QString complexItemType = itemObject[ComplexMissionItem::jsonComplexItemTypeKey].toString();
836
837 if (complexItemType == SurveyComplexItem::jsonComplexItemTypeValue) {
838 qCDebug(MissionControllerLog) << "Loading Survey: nextSequenceNumber" << nextSequenceNumber;
839 SurveyComplexItem* surveyItem = new SurveyComplexItem(_masterController, _flyView, QString() /* kmlOrShpFile */);
840 if (!surveyItem->load(itemObject, nextSequenceNumber++, errorString)) {
841 return false;
842 }
843 nextSequenceNumber = surveyItem->lastSequenceNumber() + 1;
844 qCDebug(MissionControllerLog) << "Survey load complete: nextSequenceNumber" << nextSequenceNumber;
845 visualItems->append(surveyItem);
846 } else if (complexItemType == FixedWingLandingComplexItem::jsonComplexItemTypeValue) {
847 qCDebug(MissionControllerLog) << "Loading Fixed Wing Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
849 if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
850 return false;
851 }
852 nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
853 qCDebug(MissionControllerLog) << "FW Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
854 visualItems->append(landingItem);
855 } else if (complexItemType == VTOLLandingComplexItem::jsonComplexItemTypeValue) {
856 qCDebug(MissionControllerLog) << "Loading VTOL Landing Pattern: nextSequenceNumber" << nextSequenceNumber;
858 if (!landingItem->load(itemObject, nextSequenceNumber++, errorString)) {
859 return false;
860 }
861 nextSequenceNumber = landingItem->lastSequenceNumber() + 1;
862 qCDebug(MissionControllerLog) << "VTOL Landing Pattern load complete: nextSequenceNumber" << nextSequenceNumber;
863 visualItems->append(landingItem);
864 } else if (complexItemType == StructureScanComplexItem::jsonComplexItemTypeValue) {
865 qCDebug(MissionControllerLog) << "Loading Structure Scan: nextSequenceNumber" << nextSequenceNumber;
866 StructureScanComplexItem* structureItem = new StructureScanComplexItem(_masterController, _flyView, QString() /* kmlOrShpFile */);
867 if (!structureItem->load(itemObject, nextSequenceNumber++, errorString)) {
868 return false;
869 }
870 nextSequenceNumber = structureItem->lastSequenceNumber() + 1;
871 qCDebug(MissionControllerLog) << "Structure Scan load complete: nextSequenceNumber" << nextSequenceNumber;
872 visualItems->append(structureItem);
873 } else if (complexItemType == CorridorScanComplexItem::jsonComplexItemTypeValue) {
874 qCDebug(MissionControllerLog) << "Loading Corridor Scan: nextSequenceNumber" << nextSequenceNumber;
875 CorridorScanComplexItem* corridorItem = new CorridorScanComplexItem(_masterController, _flyView, QString() /* kmlOrShpFile */);
876 if (!corridorItem->load(itemObject, nextSequenceNumber++, errorString)) {
877 return false;
878 }
879 nextSequenceNumber = corridorItem->lastSequenceNumber() + 1;
880 qCDebug(MissionControllerLog) << "Corridor Scan load complete: nextSequenceNumber" << nextSequenceNumber;
881 visualItems->append(corridorItem);
882 } else {
883 errorString = tr("Unsupported complex item type: %1").arg(complexItemType);
884 }
885 } else {
886 errorString = tr("Unknown item type: %1").arg(itemType);
887 return false;
888 }
889 }
890
891 // Fix up the DO_JUMP commands jump sequence number by finding the item with the matching doJumpId
892 for (int i=0; i<visualItems->count(); i++) {
895 if (doJumpItem->command() == MAV_CMD_DO_JUMP) {
896 bool found = false;
897 int findDoJumpId = static_cast<int>(doJumpItem->missionItem().param1());
898 for (int j=0; j<visualItems->count(); j++) {
901 if (targetItem->missionItem().doJumpId() == findDoJumpId) {
902 doJumpItem->missionItem().setParam1(targetItem->sequenceNumber());
903 found = true;
904 break;
905 }
906 }
907 }
908 if (!found) {
909 errorString = tr("Could not find doJumpId: %1").arg(findDoJumpId);
910 return false;
911 }
912 }
913 }
914 }
915
916 return true;
917}
918
919bool MissionController::_loadItemsFromJson(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
920{
921 int fileVersion;
923 _jsonFileTypeValue, // expected file type
924 2, // minimum supported version
925 2, // maximum supported version
926 fileVersion,
928
929 return _loadJsonMissionFileV2(json, visualItems, errorString);
930}
931
932bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
933{
934 bool firstItem = true;
935 bool plannedHomePositionInFile = false;
936
937 QString firstLine = stream.readLine();
938 const QStringList& version = firstLine.split(" ");
939
940 bool versionOk = false;
941 if (version.size() == 3 && version[0] == "QGC" && version[1] == "WPL") {
942 if (version[2] == "110") {
943 // ArduPilot file, planned home position is already in position 0
944 versionOk = true;
945 plannedHomePositionInFile = true;
946 } else if (version[2] == "120") {
947 // Old QGC file, no planned home position
948 versionOk = true;
949 plannedHomePositionInFile = false;
950 }
951 }
952
953 if (versionOk) {
954 MissionSettingsItem* settingsItem = _addMissionSettings(visualItems);
955
956 while (!stream.atEnd()) {
957 SimpleMissionItem* item = new SimpleMissionItem(_masterController, _flyView, true /* forLoad */);
958 if (item->load(stream)) {
959 if (firstItem && plannedHomePositionInFile) {
960 settingsItem->setInitialHomePositionFromUser(item->coordinate());
961 } else {
962 if (TakeoffMissionItem::isTakeoffCommand(static_cast<MAV_CMD>(item->command()))) {
963 // This needs to be a TakeoffMissionItem
964 TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(item->missionItem(), _masterController, _flyView, settingsItem, false /* forLoad */);
965 item->deleteLater();
966 item = takeoffItem;
967 }
968 visualItems->append(item);
969 }
970 firstItem = false;
971 } else {
972 errorString = tr("The mission file is corrupted.");
973 return false;
974 }
975 }
976 } else {
977 errorString = tr("The mission file is not compatible with this version of %1.").arg(QCoreApplication::applicationName());
978 return false;
979 }
980
981 if (!plannedHomePositionInFile) {
982 // Update sequence numbers in DO_JUMP commands to take into account added home position in index 0
983 for (int i=1; i<visualItems->count(); i++) {
984 SimpleMissionItem* item = qobject_cast<SimpleMissionItem*>(visualItems->get(i));
985 if (item && item->command() == MAV_CMD_DO_JUMP) {
986 item->missionItem().setParam1(static_cast<int>(item->missionItem().param1()) + 1);
987 }
988 }
989 }
990
991 return true;
992}
993
994void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
995{
996 if (_visualItems) {
997 _deinitAllVisualItems();
998 _visualItems->deleteLater();
999 }
1000 _settingsItem = nullptr;
1001 _takeoffMissionItem = nullptr;
1002
1003 _visualItems = loadedVisualItems;
1004
1005 if (_visualItems->count() == 0) {
1006 _addMissionSettings(_visualItems);
1007 } else {
1008 _settingsItem = _visualItems->value<MissionSettingsItem*>(0);
1009 }
1010
1011 MissionController::_scanForAdditionalSettings(_visualItems, _masterController);
1012
1013 _initAllVisualItems();
1014
1015 if (_visualItems->count() > 1) {
1016 _firstItemAdded();
1017 } else {
1018 _allItemsRemoved();
1019 }
1020}
1021
1022bool MissionController::load(const QJsonObject& json, QString& errorString)
1023{
1024 QString errorStr;
1025 QString errorMessage = tr("Mission: %1");
1026 QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);
1027
1028 if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
1029 errorString = errorMessage.arg(errorStr);
1030 return false;
1031 }
1032 _initLoadedVisualItems(loadedVisualItems);
1033
1034 return true;
1035}
1036
1038{
1039 QString errorStr;
1040 QString errorMessage = tr("Mission: %1");
1041 QByteArray bytes = file.readAll();
1042 QTextStream stream(bytes);
1043
1045
1046 QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);
1047 if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
1048 errorString = errorMessage.arg(errorStr);
1049 return false;
1050 }
1051
1052 _initLoadedVisualItems(loadedVisualItems);
1053
1054 return true;
1055}
1056
1058{
1059 for (int i=0; i<_visualItems->count(); i++) {
1060 VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1062 return visualItem->readyForSaveState();
1063 }
1064 }
1065
1067}
1068
1069void MissionController::save(QJsonObject& json)
1070{
1071 json[JsonHelper::jsonVersionKey] = _missionFileVersion;
1072
1073 // Mission settings
1074
1075 MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
1076 if (!settingsItem) {
1077 qWarning() << "First item is not MissionSettingsItem";
1078 return;
1079 }
1080 QJsonValue coordinateValue;
1081 JsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
1082 json[_jsonPlannedHomePositionKey] = coordinateValue;
1083 json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
1084 json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
1085 json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
1086 json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
1087 json[_jsonGlobalPlanAltitudeModeKey] = _globalAltMode;
1088
1089 // Save the visual items
1090
1091 QJsonArray rgJsonMissionItems;
1092 for (int i=0; i<_visualItems->count(); i++) {
1093 VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1094
1095 visualItem->save(rgJsonMissionItems);
1096 }
1097
1098 // Mission settings has a special case for end mission action
1099 if (settingsItem) {
1100 QList<MissionItem*> rgMissionItems;
1101
1102 if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
1103 QJsonObject saveObject;
1104 MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
1105 missionItem->save(saveObject);
1106 rgJsonMissionItems.append(saveObject);
1107 }
1108 for (int i=0; i<rgMissionItems.count(); i++) {
1109 rgMissionItems[i]->deleteLater();
1110 }
1111 }
1112
1113 json[_jsonItemsKey] = rgJsonMissionItems;
1114}
1115
1116void MissionController::_calcPrevWaypointValues(VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference)
1117{
1118 QGeoCoordinate currentCoord = currentItem->entryCoordinate();
1119 QGeoCoordinate prevCoord = prevItem->exitCoordinate();
1120
1121 // Convert to fixed altitudes
1122
1123 *altDifference = currentItem->amslEntryAlt() - prevItem->amslExitAlt();
1124 *distance = prevCoord.distanceTo(currentCoord);
1125 *azimuth = prevCoord.azimuthTo(currentCoord);
1126}
1127
1128double MissionController::_calcDistanceToHome(VisualMissionItem* currentItem, VisualMissionItem* homeItem)
1129{
1130 QGeoCoordinate currentCoord = currentItem->entryCoordinate();
1131 QGeoCoordinate homeCoord = homeItem->exitCoordinate();
1132 bool distanceOk = false;
1133
1134 distanceOk = true;
1135
1136 return distanceOk ? homeCoord.distanceTo(currentCoord) : 0.0;
1137}
1138
1139FlightPathSegment* MissionController::_createFlightPathSegmentWorker(VisualItemPair& pair, bool mavlinkTerrainFrame)
1140{
1141 // The takeoff goes straight up from ground to alt and then over to specified position at same alt. Which means
1142 // that coord 1 altitude is the same as coord altitude.
1143 bool takeoffStraightUp = pair.second->isTakeoffItem() && !_controllerVehicle->fixedWing();
1144
1145 QGeoCoordinate coord1 = pair.first->exitCoordinate();
1146 QGeoCoordinate coord2 = pair.second->entryCoordinate();
1147 double coord2AMSLAlt = pair.second->amslEntryAlt();
1148 double coord1AMSLAlt = takeoffStraightUp ? coord2AMSLAlt : pair.first->amslExitAlt();
1149
1151 if (pair.second->isTakeoffItem()) {
1153 } else if (pair.second->isLandCommand()) {
1155 }
1156
1157 FlightPathSegment* segment = new FlightPathSegment(segmentType, coord1, coord1AMSLAlt, coord2, coord2AMSLAlt, !_flyView /* queryTerrainData */, this);
1158
1159 if (takeoffStraightUp) {
1161 } else {
1163 }
1167
1169 connect(pair.second, &VisualMissionItem::exitCoordinateChanged, this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
1170
1171 connect(segment, &FlightPathSegment::totalDistanceChanged, this, &MissionController::recalcTerrainProfile, Qt::QueuedConnection);
1174 connect(segment, &FlightPathSegment::amslTerrainHeightsChanged, this, &MissionController::recalcTerrainProfile, Qt::QueuedConnection);
1175 connect(segment, &FlightPathSegment::terrainCollisionChanged, this, &MissionController::recalcTerrainProfile, Qt::QueuedConnection);
1176
1177 return segment;
1178}
1179
1180FlightPathSegment* MissionController::_addFlightPathSegment(FlightPathSegmentHashTable& prevItemPairHashTable, VisualItemPair& pair, bool mavlinkTerrainFrame)
1181{
1182 FlightPathSegment* segment = nullptr;
1183
1184 if (prevItemPairHashTable.contains(pair) && (prevItemPairHashTable[pair]->segmentType() == FlightPathSegment::SegmentTypeTerrainFrame) != mavlinkTerrainFrame) {
1185 // Pair already exists and connected, just re-use
1186 _flightPathSegmentHashTable[pair] = segment = prevItemPairHashTable.take(pair);
1187 } else {
1188 segment = _createFlightPathSegmentWorker(pair, mavlinkTerrainFrame);
1189 _flightPathSegmentHashTable[pair] = segment;
1190 }
1191
1192 _simpleFlightPathSegments.append(segment);
1193
1194 return segment;
1195}
1196
1197void MissionController::_recalcROISpecialVisuals(void)
1198{
1199 return;
1200 VisualMissionItem* lastCoordinateItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1201 bool roiActive = false;
1202
1203 for (int i=1; i<_visualItems->count(); i++) {
1204 VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1205 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1206 VisualItemPair viPair;
1207
1208 if (simpleItem) {
1209 if (roiActive) {
1210 if (_isROICancelItem(simpleItem)) {
1211 roiActive = false;
1212 }
1213 } else {
1214 if (_isROIBeginItem(simpleItem)) {
1215 roiActive = true;
1216 }
1217 }
1218 }
1219
1220 if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
1221 viPair = VisualItemPair(lastCoordinateItem, visualItem);
1222 if (_flightPathSegmentHashTable.contains(viPair)) {
1223 _flightPathSegmentHashTable[viPair]->setSpecialVisual(roiActive);
1224 }
1225 lastCoordinateItem = visualItem;
1226 }
1227 }
1228}
1229
1230void MissionController::_recalcFlightPathSegments(void)
1231{
1232 VisualItemPair lastSegmentVisualItemPair;
1233 int segmentCount = 0;
1234 bool firstCoordinateNotFound = true;
1235 VisualMissionItem* lastFlyThroughVI = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1236 bool linkEndToHome = false;
1237 bool linkStartToHome = _controllerVehicle->rover() ? true : false;
1238 bool foundRTL = false;
1239 bool homePositionValid = _settingsItem->coordinate().isValid();
1240 bool roiActive = false;
1241 bool previousItemIsIncomplete = false;
1242 bool signalSplitSegmentChanged = false;
1243
1244 qCDebug(MissionControllerLog) << "_recalcFlightPathSegments homePositionValid" << homePositionValid;
1245
1246 FlightPathSegmentHashTable oldSegmentTable = _flightPathSegmentHashTable;
1247
1248 _missionContainsVTOLTakeoff = false;
1249 _flightPathSegmentHashTable.clear();
1250
1251 _simpleFlightPathSegments.beginResetModel();
1252 _directionArrows.beginResetModel();
1253
1254 _simpleFlightPathSegments.clear();
1255 _directionArrows.clear();
1256
1257 // Mission Settings item needs to start with no segment
1258 lastFlyThroughVI->clearSimpleFlighPathSegment();
1259
1260 // We need to clear the simple flight path segments on all items since they are going to be rebuilt. We can't just do this in the main loop
1261 // below since that loop won't always process all items.
1262 for (int i=1; i<_visualItems->count(); i++) {
1263 qobject_cast<VisualMissionItem*>(_visualItems->get(i))->clearSimpleFlighPathSegment();
1264 }
1265
1266 // Grovel through the list of items keeping track of things needed to correctly draw waypoints lines
1267 for (int i=1; i<_visualItems->count(); i++) {
1268 VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1269 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1270 ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1271
1272 visualItem->clearSimpleFlighPathSegment();
1273
1274 if (simpleItem) {
1275 if (roiActive) {
1276 if (_isROICancelItem(simpleItem)) {
1277 roiActive = false;
1278 }
1279 } else {
1280 if (_isROIBeginItem(simpleItem)) {
1281 roiActive = true;
1282 }
1283 }
1284
1285 MAV_CMD command = simpleItem->mavCommand();
1286 switch (command) {
1287 case MAV_CMD_NAV_TAKEOFF:
1288 case MAV_CMD_NAV_VTOL_TAKEOFF:
1289 _missionContainsVTOLTakeoff = command == MAV_CMD_NAV_VTOL_TAKEOFF;
1290 if (!linkEndToHome) {
1291 // If we still haven't found the first coordinate item and we hit a takeoff command this means the mission starts from the ground.
1292 // Link the first item back to home to show that.
1293 if (firstCoordinateNotFound) {
1294 linkStartToHome = true;
1295 }
1296 }
1297 break;
1298 case MAV_CMD_NAV_RETURN_TO_LAUNCH:
1299 linkEndToHome = true;
1300 foundRTL = true;
1301 break;
1302 default:
1303 break;
1304 }
1305 }
1306
1307 // No need to add waypoint segments after an RTL.
1308 if (foundRTL) {
1309 break;
1310 }
1311
1312 // Don't draw segments immediately after a landing item
1313 if (lastFlyThroughVI->isLandCommand()) {
1314 lastFlyThroughVI = visualItem;
1315 continue;
1316 }
1317
1318 if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
1319 // Incomplete items are complex items which are waiting for the user to complete setup before there visuals can become valid.
1320 // They may not yet have valid entry/exit coordinates associated with them while in the incomplete state.
1321 // For examples a Survey item which has no polygon set yet.
1322 if (complexItem && complexItem->isIncomplete()) {
1323 // We don't link lines from a valid item to an incomplete item
1324 previousItemIsIncomplete = true;
1325 } else if (previousItemIsIncomplete) {
1326 // We also don't link lines from an incomplete item to a valid item.
1327 previousItemIsIncomplete = false;
1328 firstCoordinateNotFound = false;
1329 lastFlyThroughVI = visualItem;
1330 } else {
1331 if (lastFlyThroughVI != _settingsItem || (homePositionValid && linkStartToHome)) {
1332 bool addDirectionArrow = false;
1333 if (i != 1) {
1334 // Direction arrows are added to the second segment and every 5 segments thereafter.
1335 // The reason for start with second segment is to prevent an arrow being added in between the home position
1336 // and a takeoff item which may be right over each other. In that case the arrow points in a random direction.
1337 if (firstCoordinateNotFound || !lastFlyThroughVI->isSimpleItem() || !visualItem->isSimpleItem()) {
1338 addDirectionArrow = true;
1339 } else if (segmentCount > 5) {
1340 segmentCount = 0;
1341 addDirectionArrow = true;
1342 }
1343 segmentCount++;
1344 }
1345
1346 lastSegmentVisualItemPair = VisualItemPair(lastFlyThroughVI, visualItem);
1347 SimpleMissionItem* lastSimpleItem = qobject_cast<SimpleMissionItem*>(lastFlyThroughVI);
1348 bool mavlinkTerrainFrame = lastSimpleItem ? lastSimpleItem->missionItem().frame() == MAV_FRAME_GLOBAL_TERRAIN_ALT : false;
1349 FlightPathSegment* segment = _addFlightPathSegment(oldSegmentTable, lastSegmentVisualItemPair, mavlinkTerrainFrame);
1350 segment->setSpecialVisual(roiActive);
1351 if (addDirectionArrow) {
1352 _directionArrows.append(segment);
1353 }
1354 if (visualItem->isCurrentItem() && _delayedSplitSegmentUpdate) {
1355 _splitSegment = segment;
1356 _delayedSplitSegmentUpdate = false;
1357 signalSplitSegmentChanged = true;
1358 }
1359 lastFlyThroughVI->setSimpleFlighPathSegment(segment);
1360 }
1361 firstCoordinateNotFound = false;
1362 lastFlyThroughVI = visualItem;
1363 }
1364 }
1365 }
1366
1367 if (linkEndToHome && lastFlyThroughVI != _settingsItem && homePositionValid) {
1368 lastSegmentVisualItemPair = VisualItemPair(lastFlyThroughVI, _settingsItem);
1369 FlightPathSegment* segment = _addFlightPathSegment(oldSegmentTable, lastSegmentVisualItemPair, false /* mavlinkTerrainFrame */);
1370 segment->setSpecialVisual(roiActive);
1371 lastFlyThroughVI->setSimpleFlighPathSegment(segment);
1372 }
1373
1374 // Add direction arrow to last segment
1375 if (lastSegmentVisualItemPair.first) {
1376 FlightPathSegment* coordVector = nullptr;
1377
1378 // The pair may not be in the hash, this can happen in the fly view where only segments with arrows on them are added to hash.
1379 // check for that first and add if needed
1380
1381 if (_flightPathSegmentHashTable.contains(lastSegmentVisualItemPair)) {
1382 // Pair exists in the new table already just reuse it
1383 coordVector = _flightPathSegmentHashTable[lastSegmentVisualItemPair];
1384 } else if (oldSegmentTable.contains(lastSegmentVisualItemPair)) {
1385 // Pair already exists in old table, pull from old to new and reuse
1386 _flightPathSegmentHashTable[lastSegmentVisualItemPair] = coordVector = oldSegmentTable.take(lastSegmentVisualItemPair);
1387 } else {
1388 // Create a new segment. Since this is the fly view there is no need to wire change signals or worry about correct SegmentType
1389 coordVector = new FlightPathSegment(
1391 lastSegmentVisualItemPair.first->isSimpleItem() ? lastSegmentVisualItemPair.first->entryCoordinate() : lastSegmentVisualItemPair.first->exitCoordinate(),
1392 lastSegmentVisualItemPair.first->isSimpleItem() ? lastSegmentVisualItemPair.first->amslEntryAlt() : lastSegmentVisualItemPair.first->amslExitAlt(),
1393 lastSegmentVisualItemPair.second->entryCoordinate(),
1394 lastSegmentVisualItemPair.second->amslEntryAlt(),
1395 !_flyView /* queryTerrainData */,
1396 this);
1397 _flightPathSegmentHashTable[lastSegmentVisualItemPair] = coordVector;
1398 }
1399
1400 _directionArrows.append(coordVector);
1401 }
1402
1403 _simpleFlightPathSegments.endResetModel();
1404 _directionArrows.endResetModel();
1405
1406 // Anything left in the old table is an obsolete line object that can go
1407 qDeleteAll(oldSegmentTable);
1408
1410
1411 emit recalcTerrainProfile();
1412 if (signalSplitSegmentChanged) {
1413 emit splitSegmentChanged();
1414 }
1415}
1416
1417void MissionController::_updateBatteryInfo(int waypointIndex)
1418{
1419 if (_missionFlightStatus.mAhBattery != 0) {
1420 _missionFlightStatus.hoverAmpsTotal = (_missionFlightStatus.hoverTime / 60.0) * _missionFlightStatus.hoverAmps;
1421 _missionFlightStatus.cruiseAmpsTotal = (_missionFlightStatus.cruiseTime / 60.0) * _missionFlightStatus.cruiseAmps;
1422 _missionFlightStatus.batteriesRequired = ceil((_missionFlightStatus.hoverAmpsTotal + _missionFlightStatus.cruiseAmpsTotal) / _missionFlightStatus.ampMinutesAvailable);
1423 // FIXME: Battery change point code pretty much doesn't work. The reason is that is treats complex items as a black box. It needs to be able to look
1424 // inside complex items in order to determine a swap point that is interior to a complex item. Current the swap point display in PlanToolbar is
1425 // disabled to do this problem.
1426 if (waypointIndex != -1 && _missionFlightStatus.batteriesRequired == 2 && _missionFlightStatus.batteryChangePoint == -1) {
1427 _missionFlightStatus.batteryChangePoint = waypointIndex - 1;
1428 }
1429 }
1430}
1431
1432void MissionController::_addHoverTime(double hoverTime, double hoverDistance, int waypointIndex)
1433{
1434 _missionFlightStatus.totalTime += hoverTime;
1435 _missionFlightStatus.hoverTime += hoverTime;
1436 _missionFlightStatus.hoverDistance += hoverDistance;
1437 _missionFlightStatus.plannedDistance += hoverDistance;
1438 _updateBatteryInfo(waypointIndex);
1439}
1440
1441void MissionController::_addCruiseTime(double cruiseTime, double cruiseDistance, int waypointIndex)
1442{
1443 _missionFlightStatus.totalTime += cruiseTime;
1444 _missionFlightStatus.cruiseTime += cruiseTime;
1445 _missionFlightStatus.cruiseDistance += cruiseDistance;
1446 _missionFlightStatus.plannedDistance += cruiseDistance;
1447 _updateBatteryInfo(waypointIndex);
1448}
1449
1456void MissionController::_addTimeDistance(bool vtolInHover, double hoverTime, double cruiseTime, double extraTime, double distance, int seqNum)
1457{
1458 if (_controllerVehicle->vtol()) {
1459 if (vtolInHover) {
1460 _addHoverTime(hoverTime, distance, seqNum);
1461 _addHoverTime(extraTime, 0, -1);
1462 } else {
1463 _addCruiseTime(cruiseTime, distance, seqNum);
1464 _addCruiseTime(extraTime, 0, -1);
1465 }
1466 } else {
1467 if (_controllerVehicle->multiRotor()) {
1468 _addHoverTime(hoverTime, distance, seqNum);
1469 _addHoverTime(extraTime, 0, -1);
1470 } else {
1471 _addCruiseTime(cruiseTime, distance, seqNum);
1472 _addCruiseTime(extraTime, 0, -1);
1473 }
1474 }
1475}
1476
1477void MissionController::_recalcMissionFlightStatus()
1478{
1479 if (!_visualItems->count()) {
1480 return;
1481 }
1482
1483 bool firstCoordinateItem = true;
1484 VisualMissionItem* lastFlyThroughVI = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1485
1486 bool homePositionValid = _settingsItem->coordinate().isValid();
1487
1488 qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1489
1490 // If home position is valid we can calculate distances between all waypoints.
1491 // If home position is not valid we can only calculate distances between waypoints which are
1492 // both relative altitude.
1493
1494 // No values for first item
1495 lastFlyThroughVI->setAltDifference(0);
1496 lastFlyThroughVI->setAzimuth(0);
1497 lastFlyThroughVI->setDistance(0);
1498 lastFlyThroughVI->setDistanceFromStart(0);
1499
1500 _minAMSLAltitude = _maxAMSLAltitude = qQNaN();
1501
1502 _resetMissionFlightStatus();
1503
1504 bool linkStartToHome = false;
1505 bool foundRTL = false;
1506 bool pastLandCommand = false;
1507 double totalHorizontalDistance = 0;
1508
1509 for (int i=0; i<_visualItems->count(); i++) {
1510 VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1511 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
1512 ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(item);
1513
1514 if (simpleItem && simpleItem->mavCommand() == MAV_CMD_NAV_RETURN_TO_LAUNCH) {
1515 foundRTL = true;
1516 }
1517
1518 // Assume the worst
1519 item->setAzimuth(0);
1520 item->setDistance(0);
1521 item->setDistanceFromStart(0);
1522
1523 // Gimbal states reflect the state AFTER executing the item
1524
1525 // ROI commands cancel out previous gimbal yaw/pitch
1526 if (simpleItem) {
1527 switch (simpleItem->command()) {
1528 case MAV_CMD_NAV_ROI:
1529 case MAV_CMD_DO_SET_ROI_LOCATION:
1530 case MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET:
1531 case MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW:
1532 _missionFlightStatus.gimbalYaw = qQNaN();
1533 _missionFlightStatus.gimbalPitch = qQNaN();
1534 break;
1535 default:
1536 break;
1537 }
1538 }
1539
1540 // Look for specific gimbal changes
1541 double gimbalYaw = item->specifiedGimbalYaw();
1542 if (!qIsNaN(gimbalYaw) || _planViewSettings->showGimbalOnlyWhenSet()->rawValue().toBool()) {
1543 _missionFlightStatus.gimbalYaw = gimbalYaw;
1544 }
1545 double gimbalPitch = item->specifiedGimbalPitch();
1546 if (!qIsNaN(gimbalPitch) || _planViewSettings->showGimbalOnlyWhenSet()->rawValue().toBool()) {
1547 _missionFlightStatus.gimbalPitch = gimbalPitch;
1548 }
1549
1550 // We don't need to do any more processing if:
1551 // Mission Settings Item
1552 // We are after an RTL command
1553 if (i != 0 && !foundRTL) {
1554 // We must set the mission flight status prior to querying for any values from the item. This is because things like
1555 // current speed, gimbal, vtol state impact the values.
1556 item->setMissionFlightStatus(_missionFlightStatus);
1557
1558 // Link back to home if first item is takeoff and we have home position
1559 if (firstCoordinateItem && simpleItem && (simpleItem->mavCommand() == MAV_CMD_NAV_TAKEOFF || simpleItem->mavCommand() == MAV_CMD_NAV_VTOL_TAKEOFF)) {
1560 if (homePositionValid) {
1561 linkStartToHome = true;
1562 if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
1563 // We have to special case takeoff, assuming vehicle takes off straight up to specified altitude
1564 double azimuth, distance, altDifference;
1565 _calcPrevWaypointValues(_settingsItem, simpleItem, &azimuth, &distance, &altDifference);
1566 double takeoffTime = qAbs(altDifference) / _appSettings->offlineEditingAscentSpeed()->rawValue().toDouble();
1567 _addHoverTime(takeoffTime, 0, -1);
1568 }
1569 }
1570 }
1571
1572 if (!pastLandCommand)
1573 _addTimeDistance(_missionFlightStatus.vtolMode == QGCMAVLink::VehicleClassMultiRotor, 0, 0, item->additionalTimeDelay(), 0, -1);
1574
1575 if (item->specifiesCoordinate()) {
1576
1577 // Keep track of the min/max AMSL altitude for entire mission so we can calculate altitude percentages in terrain status display
1578 if (simpleItem) {
1579 double amslAltitude = item->amslEntryAlt();
1580 _minAMSLAltitude = std::fmin(_minAMSLAltitude, amslAltitude);
1581 _maxAMSLAltitude = std::fmax(_maxAMSLAltitude, amslAltitude);
1582 } else {
1583 // Complex item
1584 double complexMinAMSLAltitude = complexItem->minAMSLAltitude();
1585 double complexMaxAMSLAltitude = complexItem->maxAMSLAltitude();
1586 _minAMSLAltitude = std::fmin(_minAMSLAltitude, complexMinAMSLAltitude);
1587 _maxAMSLAltitude = std::fmax(_maxAMSLAltitude, complexMaxAMSLAltitude);
1588 }
1589
1590 if (!item->isStandaloneCoordinate()) {
1591 firstCoordinateItem = false;
1592
1593 // Update vehicle yaw assuming direction to next waypoint and/or mission item change
1594 if (simpleItem) {
1595 double newVehicleYaw = simpleItem->specifiedVehicleYaw();
1596 if (qIsNaN(newVehicleYaw)) {
1597 // No specific vehicle yaw set. Current vehicle yaw is determined from flight path segment direction.
1598 if (simpleItem != lastFlyThroughVI) {
1599 _missionFlightStatus.vehicleYaw = lastFlyThroughVI->exitCoordinate().azimuthTo(simpleItem->entryCoordinate());
1600 }
1601 } else {
1602 _missionFlightStatus.vehicleYaw = newVehicleYaw;
1603 }
1604 simpleItem->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1605 }
1606
1607 if (lastFlyThroughVI != _settingsItem || linkStartToHome) {
1608 // This is a subsequent waypoint or we are forcing the first waypoint back to home
1609 double azimuth, distance, altDifference;
1610
1611 _calcPrevWaypointValues(item, lastFlyThroughVI, &azimuth, &distance, &altDifference);
1612
1613 // If the last waypoint was a land command, there's a discontinuity at this point
1614 if (!lastFlyThroughVI->isLandCommand()) {
1615 totalHorizontalDistance += distance;
1616 item->setDistance(distance);
1617
1618 if (!pastLandCommand) {
1619 // Calculate time/distance
1620 double hoverTime = distance / _missionFlightStatus.hoverSpeed;
1621 double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1622 _addTimeDistance(_missionFlightStatus.vtolMode == QGCMAVLink::VehicleClassMultiRotor, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1623 }
1624 }
1625
1626 item->setAltDifference(altDifference);
1627 item->setAzimuth(azimuth);
1628 item->setDistanceFromStart(totalHorizontalDistance);
1629
1630 _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, _calcDistanceToHome(item, _settingsItem));
1631 }
1632
1633 if (complexItem) {
1634 // Add in distance/time inside complex items as well
1635 double distance = complexItem->complexDistance();
1636 _missionFlightStatus.maxTelemetryDistance = qMax(_missionFlightStatus.maxTelemetryDistance, complexItem->greatestDistanceTo(complexItem->exitCoordinate()));
1637
1638 if (!pastLandCommand) {
1639 double hoverTime = distance / _missionFlightStatus.hoverSpeed;
1640 double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1641 _addTimeDistance(_missionFlightStatus.vtolMode == QGCMAVLink::VehicleClassMultiRotor, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
1642 }
1643
1644 totalHorizontalDistance += distance;
1645 }
1646
1647
1648 lastFlyThroughVI = item;
1649 }
1650 }
1651 }
1652
1653 // Speed, VTOL states changes are processed last since they take affect on the next item
1654
1655 double newSpeed = item->specifiedFlightSpeed();
1656 if (!qIsNaN(newSpeed)) {
1657 if (_controllerVehicle->multiRotor()) {
1658 _missionFlightStatus.hoverSpeed = newSpeed;
1659 } else if (_controllerVehicle->vtol()) {
1660 if (_missionFlightStatus.vtolMode == QGCMAVLink::VehicleClassMultiRotor) {
1661 _missionFlightStatus.hoverSpeed = newSpeed;
1662 } else {
1663 _missionFlightStatus.cruiseSpeed = newSpeed;
1664 }
1665 } else {
1666 _missionFlightStatus.cruiseSpeed = newSpeed;
1667 }
1668 _missionFlightStatus.vehicleSpeed = newSpeed;
1669 }
1670
1671 // Update VTOL state
1672 if (simpleItem && _controllerVehicle->vtol()) {
1673 switch (simpleItem->command()) {
1674 case MAV_CMD_NAV_TAKEOFF: // This will do a fixed wing style takeoff
1675 case MAV_CMD_NAV_VTOL_TAKEOFF: // Vehicle goes straight up and then transitions to FW
1676 case MAV_CMD_NAV_LAND:
1677 _missionFlightStatus.vtolMode = QGCMAVLink::VehicleClassFixedWing;
1678 break;
1679 case MAV_CMD_NAV_VTOL_LAND:
1680 _missionFlightStatus.vtolMode = QGCMAVLink::VehicleClassMultiRotor;
1681 break;
1682 case MAV_CMD_DO_VTOL_TRANSITION:
1683 {
1684 int transitionState = simpleItem->missionItem().param1();
1685 if (transitionState == MAV_VTOL_STATE_MC) {
1686 _missionFlightStatus.vtolMode = QGCMAVLink::VehicleClassMultiRotor;
1687 } else if (transitionState == MAV_VTOL_STATE_FW) {
1688 _missionFlightStatus.vtolMode = QGCMAVLink::VehicleClassFixedWing;
1689 }
1690 }
1691 break;
1692 default:
1693 break;
1694 }
1695 }
1696
1697 if (item->isLandCommand()) {
1698 pastLandCommand = true;
1699 }
1700 }
1701 lastFlyThroughVI->setMissionVehicleYaw(_missionFlightStatus.vehicleYaw);
1702
1703 // Add the information for the final segment back to home
1704 if (foundRTL && lastFlyThroughVI != _settingsItem && homePositionValid) {
1705 double azimuth, distance, altDifference;
1706 _calcPrevWaypointValues(lastFlyThroughVI, _settingsItem, &azimuth, &distance, &altDifference);
1707
1708 if (!pastLandCommand) {
1709 // Calculate time/distance
1710 double hoverTime = distance / _missionFlightStatus.hoverSpeed;
1711 double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
1712 double landTime = qAbs(altDifference) / _appSettings->offlineEditingDescentSpeed()->rawValue().toDouble();
1713 _addTimeDistance(_missionFlightStatus.vtolMode == QGCMAVLink::VehicleClassMultiRotor, hoverTime, cruiseTime, landTime, distance, -1);
1714 }
1715 }
1716
1717 _missionFlightStatus.totalDistance = totalHorizontalDistance;
1718
1719 if (_missionFlightStatus.mAhBattery != 0 && _missionFlightStatus.batteryChangePoint == -1) {
1720 _missionFlightStatus.batteryChangePoint = 0;
1721 }
1722
1723 if (linkStartToHome) {
1724 // Home position is taken into account for min/max values
1725 _minAMSLAltitude = std::fmin(_minAMSLAltitude, _settingsItem->plannedHomePositionAltitude()->rawValue().toDouble());
1726 _maxAMSLAltitude = std::fmax(_maxAMSLAltitude, _settingsItem->plannedHomePositionAltitude()->rawValue().toDouble());
1727 }
1728
1729 emit missionMaxTelemetryChanged (_missionFlightStatus.maxTelemetryDistance);
1730 emit missionTotalDistanceChanged (_missionFlightStatus.totalDistance);
1731 emit missionPlannedDistanceChanged (_missionFlightStatus.plannedDistance);
1732 emit missionHoverDistanceChanged (_missionFlightStatus.hoverDistance);
1733 emit missionCruiseDistanceChanged (_missionFlightStatus.cruiseDistance);
1734 emit missionTimeChanged ();
1737 emit batteryChangePointChanged (_missionFlightStatus.batteryChangePoint);
1738 emit batteriesRequiredChanged (_missionFlightStatus.batteriesRequired);
1739 emit minAMSLAltitudeChanged (_minAMSLAltitude);
1740 emit maxAMSLAltitudeChanged (_maxAMSLAltitude);
1741
1742 // Walk the list again calculating altitude percentages
1743 double altRange = _maxAMSLAltitude - _minAMSLAltitude;
1744 for (int i=0; i<_visualItems->count(); i++) {
1745 VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1746
1747 if (item->specifiesCoordinate()) {
1748 double amslAlt = item->amslEntryAlt();
1749 if (altRange == 0.0) {
1750 item->setAltPercent(0.0);
1751 item->setTerrainPercent(qQNaN());
1752 item->setTerrainCollision(false);
1753 } else {
1754 item->setAltPercent((amslAlt - _minAMSLAltitude) / altRange);
1755 double terrainAltitude = item->terrainAltitude();
1756 if (qIsNaN(terrainAltitude)) {
1757 item->setTerrainPercent(qQNaN());
1758 item->setTerrainCollision(false);
1759 } else {
1760 item->setTerrainPercent((terrainAltitude - _minAMSLAltitude) / altRange);
1761 item->setTerrainCollision(amslAlt < terrainAltitude);
1762 }
1763 }
1764 }
1765 }
1766
1767 _updateTimer.start(UPDATE_TIMEOUT);
1768
1769 emit recalcTerrainProfile();
1770}
1771
1772// This will update the sequence numbers to be sequential starting from 0
1773void MissionController::_recalcSequence(void)
1774{
1775 if (_inRecalcSequence) {
1776 // Don't let this call recurse due to signalling
1777 return;
1778 }
1779
1780 // Setup ascending sequence numbers for all visual items
1781
1782 _inRecalcSequence = true;
1783 int sequenceNumber = 0;
1784 for (int i=0; i<_visualItems->count(); i++) {
1785 VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1786 item->setSequenceNumber(sequenceNumber);
1787 sequenceNumber = item->lastSequenceNumber() + 1;
1788 }
1789 _inRecalcSequence = false;
1790}
1791
1792// This will update the child item hierarchy
1793void MissionController::_recalcChildItems(void)
1794{
1795 VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1796
1797 currentParentItem->childItems()->clear();
1798
1799 for (int i=1; i<_visualItems->count(); i++) {
1800 VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);
1801
1802 item->setParentItem(nullptr);
1803 item->setHasCurrentChildItem(false);
1804
1805 // Set up non-coordinate item child hierarchy
1806 if (item->specifiesCoordinate()) {
1807 item->childItems()->clear();
1808 currentParentItem = item;
1809 } else if (item->isSimpleItem()) {
1810 item->setParentItem(currentParentItem);
1811 currentParentItem->childItems()->append(item);
1812 if (item->isCurrentItem()) {
1813 currentParentItem->setHasCurrentChildItem(true);
1814 }
1815 }
1816 }
1817}
1818
1819void MissionController::_setupTreeModel(void)
1820{
1821 // Tree starts empty — no need for beginReset/endReset.
1822 // We use incremental inserts so QPersistentModelIndex stays valid.
1823 _visualItemsTree.clear();
1824
1825 // ── Plan File group ──
1826 _planFileGroupNode.setObjectName(tr("Plan File"));
1827 _planFileGroupIndex = QPersistentModelIndex(
1828 _visualItemsTree.appendItem(&_planFileGroupNode, QModelIndex(), QStringLiteral("planFileGroup")));
1829
1830 _planFileInfoMarker.setObjectName(QStringLiteral("planFileInfo"));
1831 _visualItemsTree.appendItem(&_planFileInfoMarker, _planFileGroupIndex, QStringLiteral("planFileInfo"));
1832
1833 // ── Defaults group ──
1834 _defaultsGroupNode.setObjectName(tr("Defaults"));
1835 _defaultsGroupIndex = QPersistentModelIndex(
1836 _visualItemsTree.appendItem(&_defaultsGroupNode, QModelIndex(), QStringLiteral("defaultsGroup")));
1837
1838 _defaultsInfoMarker.setObjectName(QStringLiteral("defaultsInfo"));
1839 _visualItemsTree.appendItem(&_defaultsInfoMarker, _defaultsGroupIndex, QStringLiteral("defaultsInfo"));
1840
1841 // ── Mission Items group ──
1842 _missionItemsGroupNode.setObjectName(tr("Mission Items"));
1843 _missionGroupIndex = QPersistentModelIndex(
1844 _visualItemsTree.appendItem(&_missionItemsGroupNode, QModelIndex(), QStringLiteral("missionGroup")));
1845
1846 // ── GeoFence group ──
1847 _fenceGroupNode.setObjectName(tr("GeoFence"));
1848 _fenceGroupIndex = QPersistentModelIndex(
1849 _visualItemsTree.appendItem(&_fenceGroupNode, QModelIndex(), QStringLiteral("fenceGroup")));
1850
1851 // Single marker child — delegate loads the full GeoFenceEditor
1852 _fenceEditorMarker.setObjectName(QStringLiteral("fenceEditor"));
1853 _visualItemsTree.appendItem(&_fenceEditorMarker, _fenceGroupIndex, QStringLiteral("fenceEditor"));
1854
1855 // ── Rally Points group ──
1856 _rallyGroupNode.setObjectName(tr("Rally Points"));
1857 _rallyGroupIndex = QPersistentModelIndex(
1858 _visualItemsTree.appendItem(&_rallyGroupNode, QModelIndex(), QStringLiteral("rallyGroup")));
1859
1860 // Marker child for the rally header / instructions
1861 _rallyHeaderMarker.setObjectName(QStringLiteral("rallyHeader"));
1862 _visualItemsTree.appendItem(&_rallyHeaderMarker, _rallyGroupIndex, QStringLiteral("rallyHeader"));
1863}
1864
1865//-----------------------------------------------------------------------------
1866// Incremental tree model sync — Mission Items
1867//-----------------------------------------------------------------------------
1868
1869void MissionController::_onMissionItemsInserted(const QModelIndex& parent, int first, int last)
1870{
1871 Q_UNUSED(parent);
1872 for (int i = first; i <= last; i++) {
1873 auto* item = _visualItems->value<VisualMissionItem*>(i);
1874 if (item) {
1875 _visualItemsTree.insertItem(i, item, _missionGroupIndex, QStringLiteral("missionItem"));
1876 }
1877 }
1878}
1879
1880void MissionController::_onMissionItemsAboutToBeRemoved(const QModelIndex& parent, int first, int last)
1881{
1882 Q_UNUSED(parent);
1883 // Remove in reverse order so indexes stay valid
1884 for (int i = last; i >= first; i--) {
1885 _visualItemsTree.removeAt(_missionGroupIndex, i);
1886 }
1887}
1888
1889void MissionController::_onMissionItemsReset(void)
1890{
1891 // Clear mission group children and repopulate from _visualItems
1892 _visualItemsTree.removeChildren(_missionGroupIndex);
1893
1894 if (_visualItems) {
1895 for (int i = 0; i < _visualItems->count(); i++) {
1896 auto* item = _visualItems->value<VisualMissionItem*>(i);
1897 if (item) {
1898 _visualItemsTree.appendItem(item, _missionGroupIndex, QStringLiteral("missionItem"));
1899 }
1900 }
1901 }
1902}
1903
1904//-----------------------------------------------------------------------------
1905// Incremental tree model sync — Rally Points
1906//-----------------------------------------------------------------------------
1907
1908void MissionController::_onRallyPointsInserted(const QModelIndex& parent, int first, int last)
1909{
1910 Q_UNUSED(parent);
1911 auto* rallyController = _masterController->rallyPointController();
1912 if (!rallyController) return;
1913
1914 // If this is the first rally point, remove the header marker
1915 if (first == 0 && _visualItemsTree.rowCount(_rallyGroupIndex) == 1) {
1916 const QModelIndex child = _visualItemsTree.index(0, 0, _rallyGroupIndex);
1917 if (_visualItemsTree.data(child, QmlObjectTreeModel::NodeTypeRole).toString() == QStringLiteral("rallyHeader")) {
1918 _visualItemsTree.removeItem(child);
1919 }
1920 }
1921
1922 auto* pts = rallyController->points();
1923 for (int i = first; i <= last; i++) {
1924 _visualItemsTree.insertItem(i, (*pts)[i], _rallyGroupIndex, QStringLiteral("rallyItem"));
1925 }
1926}
1927
1928void MissionController::_onRallyPointsAboutToBeRemoved(const QModelIndex& parent, int first, int last)
1929{
1930 Q_UNUSED(parent);
1931 for (int i = last; i >= first; i--) {
1932 _visualItemsTree.removeAt(_rallyGroupIndex, i);
1933 }
1934
1935 // If all rally points are being removed, re-add the header marker
1936 auto* rallyController = _masterController->rallyPointController();
1937 if (rallyController && (rallyController->points()->count() - (last - first + 1)) == 0) {
1938 _rallyHeaderMarker.setObjectName(QStringLiteral("rallyHeader"));
1939 _visualItemsTree.appendItem(&_rallyHeaderMarker, _rallyGroupIndex, QStringLiteral("rallyHeader"));
1940 }
1941}
1942
1943void MissionController::_onRallyPointsReset(void)
1944{
1945 // Remove all rally children
1946 _visualItemsTree.removeChildren(_rallyGroupIndex);
1947
1948 // Repopulate — either rally items or the header marker
1949 auto* rallyController = _masterController->rallyPointController();
1950 if (rallyController && rallyController->points()->count() > 0) {
1951 auto* pts = rallyController->points();
1952 for (int i = 0; i < pts->count(); i++) {
1953 _visualItemsTree.appendItem((*pts)[i], _rallyGroupIndex, QStringLiteral("rallyItem"));
1954 }
1955 } else {
1956 _rallyHeaderMarker.setObjectName(QStringLiteral("rallyHeader"));
1957 _visualItemsTree.appendItem(&_rallyHeaderMarker, _rallyGroupIndex, QStringLiteral("rallyHeader"));
1958 }
1959}
1960
1961void MissionController::_setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate)
1962{
1963 bool foundFirstCoordinate = false;
1964 QGeoCoordinate firstCoordinate;
1965
1966 if (_settingsItem->coordinate().isValid()) {
1967 return;
1968 }
1969
1970 // Set the planned home position to be a delta from first coordinate
1971 for (int i=1; i<_visualItems->count(); i++) {
1972 VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);
1973
1974 if (item->specifiesCoordinate() && item->entryCoordinate().isValid()) {
1975 foundFirstCoordinate = true;
1976 firstCoordinate = item->entryCoordinate();
1977 break;
1978 }
1979 }
1980
1981 // No item specifying a coordinate was found, in this case it we have a clickCoordinate use that
1982 if (!foundFirstCoordinate) {
1983 firstCoordinate = clickCoordinate;
1984 }
1985
1986 if (firstCoordinate.isValid()) {
1987 QGeoCoordinate plannedHomeCoord = firstCoordinate.atDistanceAndAzimuth(30, 0);
1988 plannedHomeCoord.setAltitude(0);
1989 _settingsItem->setInitialHomePositionFromUser(plannedHomeCoord);
1990 }
1991}
1992
1993void MissionController::_recalcAllWithCoordinate(const QGeoCoordinate& coordinate)
1994{
1995 if (!_flyView) {
1996 _setPlannedHomePositionFromFirstCoordinate(coordinate);
1997 }
1998 _recalcSequence();
1999 _recalcChildItems();
2001 _updateTimer.start(UPDATE_TIMEOUT);
2002}
2003
2004void MissionController::_recalcAll(void)
2005{
2006 QGeoCoordinate emptyCoord;
2007 _recalcAllWithCoordinate(emptyCoord);
2008}
2009
2011void MissionController::_initAllVisualItems(void)
2012{
2013 // Setup home position at index 0
2014
2015 if (!_settingsItem) {
2016 _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
2017 if (!_settingsItem) {
2018 qWarning() << "First item not MissionSettingsItem";
2019 return;
2020 }
2021 }
2022
2023 connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcMissionFlightStatus);
2025
2026 for (int i=0; i<_visualItems->count(); i++) {
2027 VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
2028 _initVisualItem(item);
2029
2030 TakeoffMissionItem* takeoffItem = qobject_cast<TakeoffMissionItem*>(item);
2031 if (takeoffItem) {
2032 _takeoffMissionItem = takeoffItem;
2033 }
2034 }
2035
2036 _recalcAll();
2037
2038 connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
2039 connect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
2040
2041 // Connect for incremental tree model sync
2042 connect(_visualItems, &QAbstractItemModel::rowsInserted, this, &MissionController::_onMissionItemsInserted);
2043 connect(_visualItems, &QAbstractItemModel::rowsAboutToBeRemoved, this, &MissionController::_onMissionItemsAboutToBeRemoved);
2044 connect(_visualItems, &QAbstractItemModel::modelReset, this, &MissionController::_onMissionItemsReset);
2045
2046 // Populate tree's mission group from current _visualItems
2047 _onMissionItemsReset();
2048
2049 // Connect rally controller for incremental tree model sync
2050 auto* rallyController = _masterController->rallyPointController();
2051 if (rallyController) {
2052 auto* pts = rallyController->points();
2053 connect(pts, &QAbstractItemModel::rowsInserted, this, &MissionController::_onRallyPointsInserted);
2054 connect(pts, &QAbstractItemModel::rowsAboutToBeRemoved, this, &MissionController::_onRallyPointsAboutToBeRemoved);
2055 connect(pts, &QAbstractItemModel::modelReset, this, &MissionController::_onRallyPointsReset);
2056
2057 // Populate any existing rally points
2058 _onRallyPointsReset();
2059 }
2060
2061 emit visualItemsChanged();
2062 emit containsItemsChanged();
2064
2065 if (!_flyView) {
2066 setCurrentPlanViewSeqNum(0, true);
2067 }
2068
2069 setDirty(false);
2070}
2071
2072void MissionController::_deinitAllVisualItems(void)
2073{
2074 disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
2076
2077 for (int i=0; i<_visualItems->count(); i++) {
2078 _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
2079 }
2080
2081 disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
2082 disconnect(_visualItems, &QmlObjectListModel::countChanged, this, &MissionController::_updateContainsItems);
2083
2084 // Disconnect incremental tree model sync
2085 disconnect(_visualItems, &QAbstractItemModel::rowsInserted, this, &MissionController::_onMissionItemsInserted);
2086 disconnect(_visualItems, &QAbstractItemModel::rowsAboutToBeRemoved, this, &MissionController::_onMissionItemsAboutToBeRemoved);
2087 disconnect(_visualItems, &QAbstractItemModel::modelReset, this, &MissionController::_onMissionItemsReset);
2088
2089 // Disconnect rally controller tree model sync
2090 auto* rallyController = _masterController->rallyPointController();
2091 if (rallyController) {
2092 auto* pts = rallyController->points();
2093 disconnect(pts, &QAbstractItemModel::rowsInserted, this, &MissionController::_onRallyPointsInserted);
2094 disconnect(pts, &QAbstractItemModel::rowsAboutToBeRemoved, this, &MissionController::_onRallyPointsAboutToBeRemoved);
2095 disconnect(pts, &QAbstractItemModel::modelReset, this, &MissionController::_onRallyPointsReset);
2096 }
2097}
2098
2099void MissionController::_initVisualItem(VisualMissionItem* visualItem)
2100{
2101 setDirty(false);
2102
2111 connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged, this, &MissionController::_recalcSequence);
2112
2113 if (visualItem->isSimpleItem()) {
2114 // We need to track commandChanged on simple item since recalc has special handling for takeoff command
2115 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
2116 if (simpleItem) {
2117 connect(&simpleItem->missionItem()._commandFact, &Fact::valueChanged, this, &MissionController::_itemCommandChanged);
2118 } else {
2119 qWarning() << "isSimpleItem == true, yet not SimpleMissionItem";
2120 }
2121 } else {
2122 ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
2123 if (complexItem) {
2128 connect(complexItem, &ComplexMissionItem::isIncompleteChanged, this, &MissionController::_recalcFlightPathSegmentsSignal, Qt::QueuedConnection);
2129 } else {
2130 qWarning() << "ComplexMissionItem not found";
2131 }
2132 }
2133}
2134
2135void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
2136{
2137 // Disconnect only signals connected to this MissionController, not all receivers.
2138 // A full wildcard disconnect(obj, 0, 0, 0) tears out internal destroyed-signal
2139 // connections that Qt (and the tree/list models) rely on for cleanup.
2140 disconnect(visualItem, nullptr, this, nullptr);
2141}
2142
2143void MissionController::_itemCommandChanged(void)
2144{
2145 _recalcChildItems();
2147}
2148
2149void MissionController::_managerVehicleChanged(Vehicle* managerVehicle)
2150{
2151 if (_managerVehicle) {
2152 _missionManager->disconnect(this);
2153 _managerVehicle->disconnect(this);
2154 _managerVehicle = nullptr;
2155 _missionManager = nullptr;
2156 }
2157
2158 _managerVehicle = managerVehicle;
2159 if (!_managerVehicle) {
2160 qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
2161 return;
2162 }
2163
2164 _missionManager = _managerVehicle->missionManager();
2165 connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
2166 connect(_missionManager, &MissionManager::sendComplete, this, &MissionController::_managerSendComplete);
2167 connect(_missionManager, &MissionManager::removeAllComplete, this, &MissionController::_managerRemoveAllComplete);
2168 connect(_missionManager, &MissionManager::inProgressChanged, this, &MissionController::_inProgressChanged);
2169 connect(_missionManager, &MissionManager::progressPctChanged, this, &MissionController::_progressPctChanged);
2170 connect(_missionManager, &MissionManager::currentIndexChanged, this, &MissionController::_currentMissionIndexChanged);
2174 connect(_managerVehicle, &Vehicle::defaultCruiseSpeedChanged, this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
2175 connect(_managerVehicle, &Vehicle::defaultHoverSpeedChanged, this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
2177
2180}
2181
2182void MissionController::_inProgressChanged(bool inProgress)
2183{
2184 emit syncInProgressChanged(inProgress);
2185}
2186
2187bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, QGroundControlQmlGlobal::AltMode* prevAltitudeMode)
2188{
2189 bool found = false;
2190 double foundAltitude = 0;
2192
2193 if (newIndex > _visualItems->count()) {
2194 return false;
2195 }
2196 newIndex--;
2197
2198 for (int i=newIndex; i>0; i--) {
2199 VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
2200
2201 if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
2202 if (visualItem->isSimpleItem()) {
2203 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
2204 if (simpleItem->specifiesAltitude()) {
2205 foundAltitude = simpleItem->altitude()->rawValue().toDouble();
2206 foundAltMode = simpleItem->altitudeMode();
2207 found = true;
2208 break;
2209 }
2210 }
2211 }
2212 }
2213
2214 if (found) {
2215 *prevAltitude = foundAltitude;
2216 *prevAltitudeMode = foundAltMode;
2217 }
2218
2219 return found;
2220}
2221
2222double MissionController::_normalizeLat(double lat)
2223{
2224 // Normalize latitude to range: 0 to 180, S to N
2225 return lat + 90.0;
2226}
2227
2228double MissionController::_normalizeLon(double lon)
2229{
2230 // Normalize longitude to range: 0 to 360, W to E
2231 return lon + 180.0;
2232}
2233
2235MissionSettingsItem* MissionController::_addMissionSettings(QmlObjectListModel* visualItems)
2236{
2237 qCDebug(MissionControllerLog) << "_addMissionSettings";
2238
2240 visualItems->insert(0, settingsItem);
2241
2242 if (visualItems == _visualItems) {
2243 _settingsItem = settingsItem;
2244 }
2245
2246 return settingsItem;
2247}
2248
2249void MissionController::_centerHomePositionOnMissionItems(QmlObjectListModel *visualItems)
2250{
2251 qCDebug(MissionControllerLog) << "_centerHomePositionOnMissionItems";
2252
2253 if (visualItems->count() > 1) {
2254 double north = 0.0;
2255 double south = 0.0;
2256 double east = 0.0;
2257 double west = 0.0;
2258 bool firstCoordSet = false;
2259
2260 for (int i=1; i<visualItems->count(); i++) {
2261 VisualMissionItem* item = qobject_cast<VisualMissionItem*>(visualItems->get(i));
2262 if (item->specifiesCoordinate()) {
2263 if (firstCoordSet) {
2264 double lat = _normalizeLat(item->entryCoordinate().latitude());
2265 double lon = _normalizeLon(item->entryCoordinate().longitude());
2266 north = fmax(north, lat);
2267 south = fmin(south, lat);
2268 east = fmax(east, lon);
2269 west = fmin(west, lon);
2270 } else {
2271 firstCoordSet = true;
2272 north = _normalizeLat(item->entryCoordinate().latitude());
2273 south = north;
2274 east = _normalizeLon(item->entryCoordinate().longitude());
2275 west = east;
2276 }
2277 }
2278 }
2279
2280 if (firstCoordSet) {
2281 _settingsItem->setInitialHomePositionFromUser(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
2282 }
2283 }
2284}
2285
2287{
2288
2289 int resumeIndex = 0;
2290
2291 if (_flyView) {
2292 resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
2293 if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
2294 // Resume at the item previous to the item we were heading towards
2295 resumeIndex--;
2296 } else {
2297 resumeIndex = 0;
2298 }
2299 }
2300
2301 return resumeIndex;
2302}
2303
2305{
2306 if (!_flyView) {
2307 return -1;
2308 } else {
2309 int currentIndex = _missionManager->currentIndex();
2310 if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
2311 currentIndex++;
2312 }
2313 return currentIndex;
2314 }
2315}
2316
2317void MissionController::_currentMissionIndexChanged(int sequenceNumber)
2318{
2319 if (_flyView) {
2320 if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
2321 sequenceNumber++;
2322 }
2323
2324 for (int i=0; i<_visualItems->count(); i++) {
2325 VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
2326 item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
2327 }
2329 }
2330}
2331
2333{
2334 return _missionManager->inProgress();
2335}
2336
2338{
2339 return _visualItems ? _visualItems->dirty() : false;
2340}
2341
2342
2344{
2345 if (_visualItems) {
2346 _visualItems->setDirty(dirty);
2347 }
2348}
2349
2350void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, PlanMasterController* masterController)
2351{
2352 // First we look for Landing Patterns which are at the end
2355 }
2356
2357 int scanIndex = 0;
2358 while (scanIndex < visualItems->count()) {
2359 VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);
2360
2361 qCDebug(MissionControllerLog) << "MissionController::_scanForAdditionalSettings count:scanIndex" << visualItems->count() << scanIndex;
2362
2363 if (!_flyView) {
2364 MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
2365 if (settingsItem) {
2366 scanIndex++;
2367 settingsItem->scanForMissionSettings(visualItems, scanIndex);
2368 continue;
2369 }
2370 }
2371
2372 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
2373 if (simpleItem) {
2374 scanIndex++;
2375 simpleItem->scanForSections(visualItems, scanIndex, masterController);
2376 } else {
2377 // Complex item, can't have sections
2378 scanIndex++;
2379 }
2380 }
2381}
2382
2383void MissionController::_updateContainsItems(void)
2384{
2385 emit containsItemsChanged();
2386}
2387
2389{
2390 return _visualItems ? _visualItems->count() > 1 : false;
2391}
2392
2394{
2395 if (_masterController->offline()) {
2396 qCCritical(MissionControllerLog) << "MissionControllerLog::removeAllFromVehicle called while offline";
2397 } else if (syncInProgress()) {
2398 qCCritical(MissionControllerLog) << "MissionControllerLog::removeAllFromVehicle called while syncInProgress";
2399 } else {
2400 _itemsRequested = true;
2401 _missionManager->removeAll();
2402 }
2403}
2404
2406{
2407 QStringList complexItems;
2408
2409 complexItems.append(SurveyComplexItem::name);
2410 complexItems.append(CorridorScanComplexItem::name);
2411 if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) {
2412 complexItems.append(StructureScanComplexItem::name);
2413 }
2414
2415 // Note: The landing pattern items are not added here since they have there own button which adds them
2416
2417 return QGCCorePlugin::instance()->complexMissionItemNames(_controllerVehicle, complexItems);
2418}
2419
2421{
2422 if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
2423 resumeIndex--;
2424 }
2425 _missionManager->generateResumeMission(resumeIndex);
2426}
2427
2429{
2430 if (_settingsItem) {
2431 return _settingsItem->coordinate();
2432 } else {
2433 return QGeoCoordinate();
2434 }
2435}
2436
2438{
2439 double defaultAltitude = _appSettings->defaultMissionItemAltitude()->rawValue().toDouble();
2440
2441 for (int i=1; i<_visualItems->count(); i++) {
2442 VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);
2443 item->applyNewAltitude(defaultAltitude);
2444 }
2445}
2446
2447void MissionController::_progressPctChanged(double progressPct)
2448{
2449 if (!QGC::fuzzyCompare(progressPct, _progressPct)) {
2450 _progressPct = progressPct;
2452 }
2453}
2454
2455void MissionController::_visualItemsDirtyChanged(bool dirty)
2456{
2457 // We could connect signal to signal and not need this but this is handy for setting a breakpoint on
2458 emit dirtyChanged(dirty);
2459}
2460
2462{
2463 qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
2464 if (_masterController->offline()) {
2465 qCCritical(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
2466 return true; // stops further propagation of showPlanFromManagerVehicle due to error
2467 } else {
2468 if (!_managerVehicle->initialPlanRequestComplete()) {
2469 // The vehicle hasn't completed initial load, we can just wait for newMissionItemsAvailable to be signalled automatically
2470 qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle: !initialPlanRequestComplete, wait for signal";
2471 return true;
2472 } else if (syncInProgress()) {
2473 // If the sync is already in progress, newMissionItemsAvailable will be signalled automatically when it is done. So no need to do anything.
2474 qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle: syncInProgress wait for signal";
2475 return true;
2476 } else {
2477 // Fake a _newMissionItemsAvailable with the current items
2478 qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle: sync complete simulate signal";
2479 _itemsRequested = true;
2480 _newMissionItemsAvailableFromVehicle(false /* removeAllRequested */);
2481 return false;
2482 }
2483 }
2484}
2485
2486void MissionController::_managerSendComplete(bool error)
2487{
2488 // Fly view always reloads on send complete
2489 if (!error && _flyView) {
2491 }
2492}
2493
2494void MissionController::_managerRemoveAllComplete(bool error)
2495{
2496 if (!error) {
2497 // Remove all from vehicle so we always update
2499 }
2500}
2501
2502bool MissionController::_isROIBeginItem(SimpleMissionItem* simpleItem)
2503{
2504 return simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI_LOCATION ||
2505 simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET ||
2506 (simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI &&
2507 static_cast<int>(simpleItem->missionItem().param1()) == MAV_ROI_LOCATION);
2508}
2509
2510bool MissionController::_isROICancelItem(SimpleMissionItem* simpleItem)
2511{
2512 return simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI_NONE ||
2513 (simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI &&
2514 static_cast<int>(simpleItem->missionItem().param1()) == MAV_ROI_NONE);
2515}
2516
2517void MissionController::setCurrentPlanViewSeqNum(int sequenceNumber, bool force)
2518{
2519 if (_visualItems && (force || sequenceNumber != _currentPlanViewSeqNum)) {
2520 qCDebug(MissionControllerLog) << "setCurrentPlanViewSeqNum";
2521 bool foundLand = false;
2522 int takeoffSeqNum = -1;
2523 int landSeqNum = -1;
2524 int lastFlyThroughSeqNum = -1;
2525
2526 _splitSegment = nullptr;
2527 _currentPlanViewItem = nullptr;
2528 _currentPlanViewSeqNum = -1;
2529 _currentPlanViewVIIndex = -1;
2530 _onlyInsertTakeoffValid = false;
2531 _isInsertTakeoffValid = true;
2532 _isInsertLandValid = true;
2533 _isROIActive = false;
2534 _isROIBeginCurrentItem = false;
2535 _flyThroughCommandsAllowed = true;
2536 _previousCoordinate = QGeoCoordinate();
2537
2538 bool noItemsAddedYet = _visualItems->count() == 1;
2539 if (_masterController->controllerVehicle()->supports()->takeoffMissionCommand() && !_planViewSettings->takeoffItemNotRequired()->rawValue().toBool() && noItemsAddedYet) {
2540 _onlyInsertTakeoffValid = true;
2541 }
2542
2543 for (int viIndex=0; viIndex<_visualItems->count(); viIndex++) {
2544 VisualMissionItem* pVI = qobject_cast<VisualMissionItem*>(_visualItems->get(viIndex));
2545 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(pVI);
2546 int currentSeqNumber = pVI->sequenceNumber();
2547
2548 if (sequenceNumber != 0 && currentSeqNumber <= sequenceNumber) {
2549 if (pVI->specifiesCoordinate() && !pVI->isStandaloneCoordinate()) {
2550 // Coordinate based flight commands prior to where the takeoff would be inserted
2551 _isInsertTakeoffValid = false;
2552 }
2553 }
2554
2555 if (qobject_cast<TakeoffMissionItem*>(pVI)) {
2556 takeoffSeqNum = currentSeqNumber;
2557 _isInsertTakeoffValid = false;
2558 }
2559
2560 if (!foundLand) {
2561 if (simpleItem) {
2562 switch (simpleItem->mavCommand()) {
2563 case MAV_CMD_NAV_LAND:
2564 case MAV_CMD_NAV_VTOL_LAND:
2565 case MAV_CMD_DO_LAND_START:
2566 case MAV_CMD_NAV_RETURN_TO_LAUNCH:
2567 foundLand = true;
2568 landSeqNum = currentSeqNumber;
2569 break;
2570 default:
2571 break;
2572 }
2573 } else {
2574 FixedWingLandingComplexItem* fwLanding = qobject_cast<FixedWingLandingComplexItem*>(pVI);
2575 if (fwLanding) {
2576 foundLand = true;
2577 landSeqNum = currentSeqNumber;
2578 }
2579 }
2580 }
2581
2582 if (simpleItem) {
2583 // Remember previous coordinate
2584 if (currentSeqNumber < sequenceNumber && simpleItem->specifiesCoordinate() && !simpleItem->isStandaloneCoordinate()) {
2585 _previousCoordinate = simpleItem->coordinate();
2586 }
2587
2588 // ROI state handling
2589 if (currentSeqNumber <= sequenceNumber) {
2590 if (_isROIActive) {
2591 if (_isROICancelItem(simpleItem)) {
2592 _isROIActive = false;
2593 }
2594 } else {
2595 if (_isROIBeginItem(simpleItem)) {
2596 _isROIActive = true;
2597 }
2598 }
2599 }
2600 if (currentSeqNumber == sequenceNumber && _isROIBeginItem(simpleItem)) {
2601 _isROIBeginCurrentItem = true;
2602 }
2603 }
2604
2605 if (viIndex != 0) {
2606 // Complex items are assumed to be fly through
2607 if (!simpleItem || (simpleItem->specifiesCoordinate() && !simpleItem->isStandaloneCoordinate())) {
2608 lastFlyThroughSeqNum = currentSeqNumber;
2609 }
2610 }
2611
2612 if (currentSeqNumber == sequenceNumber) {
2613 pVI->setIsCurrentItem(true);
2614 pVI->setHasCurrentChildItem(false);
2615
2616 _currentPlanViewItem = pVI;
2617 _currentPlanViewSeqNum = sequenceNumber;
2618 _currentPlanViewVIIndex = viIndex;
2619
2620 if (pVI->specifiesCoordinate()) {
2621 if (!pVI->isStandaloneCoordinate()) {
2622 // Determine split segment used to display line split editing ui.
2623 for (int j=viIndex-1; j>0; j--) {
2624 VisualMissionItem* pPrev = qobject_cast<VisualMissionItem*>(_visualItems->get(j));
2625 if (pPrev->specifiesCoordinate() && !pPrev->isStandaloneCoordinate()) {
2626 VisualItemPair splitPair(pPrev, pVI);
2627 if (_flightPathSegmentHashTable.contains(splitPair)) {
2628 _splitSegment = _flightPathSegmentHashTable[splitPair];
2629 } else {
2630 // The recalc of flight path segments hasn't happened yet since it is delayed and compressed.
2631 // So we need to register the fact that we need a split segment update and it will happen in the recalc instead.
2632 _delayedSplitSegmentUpdate = true;
2633 }
2634 break;
2635 }
2636 }
2637 }
2638 } else if (pVI->parentItem()) {
2639 pVI->parentItem()->setHasCurrentChildItem(true);
2640 }
2641 } else {
2642 pVI->setIsCurrentItem(false);
2643 // Child items will always be later in the mission sequence, so this should be correct, to be sure the HasCurrentChildItem is cleared
2644 pVI->setHasCurrentChildItem(false);
2645 }
2646 }
2647
2648 if (takeoffSeqNum != -1) {
2649 // Takeoff item was found which means mission starts from ground
2650 if (sequenceNumber < takeoffSeqNum) {
2651 // Land is only valid after the takeoff item.
2652 _isInsertLandValid = false;
2653 // Fly through commands are not allowed prior to the takeoff command
2654 _flyThroughCommandsAllowed = false;
2655 }
2656 }
2657
2658 if (lastFlyThroughSeqNum != -1) {
2659 // Land item must be after any fly through coordinates
2660 if (sequenceNumber < lastFlyThroughSeqNum) {
2661 _isInsertLandValid = false;
2662 }
2663 }
2664
2665 if (foundLand && !multipleLandPatternsAllowed()) {
2666 _isInsertLandValid = false;
2667 if (sequenceNumber >= landSeqNum) {
2668 // Can't have fly through commands after a land item
2669 _flyThroughCommandsAllowed = false;
2670 }
2671 }
2672
2673 if (_hasLandItem != foundLand) {
2674 // Update hasLandItem if the presence of a landing item has changed
2675 _hasLandItem = foundLand;
2676 emit hasLandItemChanged();
2677 }
2678
2679 // These are not valid when only takeoff is allowed
2680 _isInsertLandValid = _isInsertLandValid && !_onlyInsertTakeoffValid;
2681 _flyThroughCommandsAllowed = _flyThroughCommandsAllowed && !_onlyInsertTakeoffValid;
2682
2686 emit splitSegmentChanged();
2690 emit isROIActiveChanged();
2694 }
2695}
2696
2697void MissionController::repositionMission(const QGeoCoordinate& newHome,
2698 bool repositionTakeoffItems,
2699 bool repositionLandingItems)
2700{
2701 if (!newHome.isValid()) {
2702 qCWarning(MissionControllerLog) << "Cannot reposition mission to an invalid coordinate";
2703 return;
2704 }
2705
2706 if (!_settingsItem || !_settingsItem->coordinate().isValid()) {
2707 qCWarning(MissionControllerLog) << "Cannot reposition mission while home is invalid";
2708 return;
2709 }
2710
2711 const QGeoCoordinate oldHome = _settingsItem->coordinate();
2712
2713 for (int i = 0; i < _visualItems->count(); ++i) {
2714 auto* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
2715 if (!item || !item->specifiesCoordinate() || item->isStandaloneCoordinate()) {
2716 continue;
2717 }
2718
2719 if ((!repositionTakeoffItems && item->isTakeoffItem()) ||
2720 (!repositionLandingItems && item->isLandCommand())) {
2721 continue;
2722 }
2723
2724 const QGeoCoordinate oldCoord = item->coordinate();
2725 if (!oldCoord.isValid()) {
2726 continue;
2727 }
2728
2729 const double distanceMeters = oldHome.distanceTo(oldCoord);
2730 const double azimuthDegrees = oldHome.azimuthTo(oldCoord);
2731
2732 QGeoCoordinate newCoord = newHome.atDistanceAndAzimuth(distanceMeters, azimuthDegrees);
2733 item->setCoordinate(newCoord);
2734 }
2735
2736 setDirty(true);
2737}
2738
2740 double northMeters,
2741 double upMeters,
2742 bool offsetTakeoffItems,
2743 bool offsetLandingItems)
2744{
2745 if (!_settingsItem || !_settingsItem->coordinate().isValid()) {
2746 qCWarning(MissionControllerLog) << "Cannot offset mission while home is invalid";
2747 return;
2748 }
2749
2750 if (!qFuzzyIsNull(eastMeters) || !qFuzzyIsNull(northMeters)) {
2751 double distanceMeters = qSqrt(eastMeters * eastMeters + northMeters * northMeters);
2752 double azimuthDegrees = 0.0;
2753 if (!qFuzzyIsNull(distanceMeters)) {
2754 const double azimuthRadians = qAtan2(eastMeters, northMeters);
2755 azimuthDegrees = qRadiansToDegrees(azimuthRadians);
2756 }
2757
2758 const QGeoCoordinate oldHome = _settingsItem->coordinate();
2759 QGeoCoordinate newHome = oldHome.atDistanceAndAzimuth(distanceMeters, azimuthDegrees);
2760 repositionMission(newHome, offsetTakeoffItems, offsetLandingItems);
2761 }
2762
2763 if (!qFuzzyIsNull(upMeters)) {
2764 for (int i = 0; i < _visualItems->count(); ++i) {
2765 auto* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
2766 if (!item || item == _settingsItem) {
2767 continue;
2768 }
2769
2770 if ((!offsetTakeoffItems && item->isTakeoffItem()) ||
2771 (!offsetLandingItems && item->isLandCommand())) {
2772 continue;
2773 }
2774
2775 if (!item->specifiesCoordinate() && !item->specifiesAltitudeOnly()) {
2776 continue;
2777 }
2778
2779 if (!qIsNaN(item->editableAlt())) {
2780 item->applyNewAltitude(item->editableAlt() + upMeters);
2781 }
2782 }
2783 }
2784}
2785
2787 bool rotateTakeoffItems,
2788 bool rotateLandingItems)
2789{
2790 if (qFuzzyIsNull(degreesCW)) {
2791 return;
2792 }
2793
2794 if (!_settingsItem || !_settingsItem->coordinate().isValid()) {
2795 qCWarning(MissionControllerLog) << "Cannot rotate mission while home is invalid";
2796 return;
2797 }
2798
2799 const QGeoCoordinate home = _settingsItem->coordinate();
2800
2801 for (int i = 0; i < _visualItems->count(); ++i) {
2802 auto* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
2803 if (!item || !item->specifiesCoordinate() || item->isStandaloneCoordinate()) {
2804 continue;
2805 }
2806
2807 if ((!rotateTakeoffItems && item->isTakeoffItem()) ||
2808 (!rotateLandingItems && item->isLandCommand())) {
2809 continue;
2810 }
2811
2812 const QGeoCoordinate oldCoord = item->coordinate();
2813 if (!oldCoord.isValid()) {
2814 continue;
2815 }
2816
2817 const double distanceMeters = home.distanceTo(oldCoord);
2818 if (qFuzzyIsNull(distanceMeters)) {
2819 continue;
2820 }
2821 const double azimuthDegrees = home.azimuthTo(oldCoord);
2822
2823 QGeoCoordinate newCoord = home.atDistanceAndAzimuth(distanceMeters, azimuthDegrees + degreesCW);
2824 item->setCoordinate(newCoord);
2825 }
2826
2827 setDirty(true);
2828}
2829
2830void MissionController::_updateTimeout()
2831{
2832 QGeoCoordinate firstCoordinate;
2833 QGeoCoordinate takeoffCoordinate;
2834 QGCGeoBoundingCube boundingCube;
2835 double north = 0.0;
2836 double south = 180.0;
2837 double east = 0.0;
2838 double west = 360.0;
2839 double minAlt = QGCGeoBoundingCube::MaxAlt;
2840 double maxAlt = QGCGeoBoundingCube::MinAlt;
2841 for (int i = 1; i < _visualItems->count(); i++) {
2842 VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
2843 if(item->isSimpleItem()) {
2844 SimpleMissionItem* pSimpleItem = qobject_cast<SimpleMissionItem*>(item);
2845 if(pSimpleItem) {
2846 switch(pSimpleItem->command()) {
2847 case MAV_CMD_NAV_TAKEOFF:
2848 case MAV_CMD_NAV_WAYPOINT:
2849 case MAV_CMD_NAV_LAND:
2850 if(pSimpleItem->coordinate().isValid()) {
2851 double alt = 0.0;
2852 if (!pSimpleItem->altitude()->rawValue().isNull() && !qIsNaN(pSimpleItem->altitude()->rawValue().toDouble())) {
2853 alt = pSimpleItem->altitude()->rawValue().toDouble();
2854 }
2855 if((MAV_CMD)pSimpleItem->command() == MAV_CMD_NAV_TAKEOFF) {
2856 takeoffCoordinate = pSimpleItem->coordinate();
2857 takeoffCoordinate.setAltitude(alt);
2858 minAlt = maxAlt = alt;
2859 } else if(!firstCoordinate.isValid()) {
2860 firstCoordinate = pSimpleItem->coordinate();
2861 }
2862 double lat = pSimpleItem->coordinate().latitude() + 90.0;
2863 double lon = pSimpleItem->coordinate().longitude() + 180.0;
2864 north = fmax(north, lat);
2865 south = fmin(south, lat);
2866 east = fmax(east, lon);
2867 west = fmin(west, lon);
2868 minAlt = fmin(minAlt, alt);
2869 maxAlt = fmax(maxAlt, alt);
2870 }
2871 break;
2872 default:
2873 break;
2874 }
2875 }
2876 } else {
2877 ComplexMissionItem* pComplexItem = qobject_cast<ComplexMissionItem*>(item);
2878 if(pComplexItem) {
2879 QGCGeoBoundingCube bc = pComplexItem->boundingCube();
2880 if(bc.isValid()) {
2881 if(!firstCoordinate.isValid() && pComplexItem->entryCoordinate().isValid()) {
2882 firstCoordinate = pComplexItem->entryCoordinate();
2883 }
2884 north = fmax(north, bc.pointNW.latitude() + 90.0);
2885 south = fmin(south, bc.pointSE.latitude() + 90.0);
2886 east = fmax(east, bc.pointNW.longitude() + 180.0);
2887 west = fmin(west, bc.pointSE.longitude() + 180.0);
2888 minAlt = fmin(minAlt, bc.pointNW.altitude());
2889 maxAlt = fmax(maxAlt, bc.pointSE.altitude());
2890 }
2891 }
2892 }
2893 }
2894 //-- Figure out where this thing is taking off from
2895 if(!takeoffCoordinate.isValid()) {
2896 if(firstCoordinate.isValid()) {
2897 takeoffCoordinate = firstCoordinate;
2898 } else {
2900 }
2901 }
2902 //-- Build bounding "cube"
2903 boundingCube = QGCGeoBoundingCube(
2904 QGeoCoordinate(north - 90.0, west - 180.0, minAlt),
2905 QGeoCoordinate(south - 90.0, east - 180.0, maxAlt));
2906 if(_travelBoundingCube != boundingCube || _takeoffCoordinate != takeoffCoordinate) {
2907 _takeoffCoordinate = takeoffCoordinate;
2908 _travelBoundingCube = boundingCube;
2910 qCDebug(MissionControllerLog) << "Bounding cube:" << _travelBoundingCube.pointNW << _travelBoundingCube.pointSE;
2911 }
2912}
2913
2914void MissionController::_complexBoundingBoxChanged()
2915{
2916 _updateTimer.start(UPDATE_TIMEOUT);
2917}
2918
2920 const int count = _visualItems->count();
2921
2922 for (int i = 0; i < count; i++) {
2923 QObject *obj = _visualItems->get(i);
2924
2925 LandingComplexItem *landingItem = qobject_cast<LandingComplexItem *>(obj);
2926 if (landingItem) {
2927 return landingItem == item;
2928 }
2929 }
2930
2931 return false;
2932}
2933
2935{
2936 return _visualItems->count() <= 1;
2937}
2938
2939void MissionController::_forceRecalcOfAllowedBits(void)
2940{
2941 // Force a recalc of allowed bits
2942 setCurrentPlanViewSeqNum(_currentPlanViewSeqNum, true /* force */);
2943}
2944
2946{
2948}
2949
2954
2959
2960void MissionController::_allItemsRemoved(void)
2961{
2962 // When there are no mission items we track changes to firmware/vehicle type. This allows a vehicle connection
2963 // to adjust these items.
2964 _controllerVehicle->trackFirmwareVehicleTypeChanges();
2965}
2966
2967void MissionController::_firstItemAdded(void)
2968{
2969 // As soon as the first item is added we lock the firmware/vehicle type to current values. So if you then connect a vehicle
2970 // it will not affect these values.
2971 _controllerVehicle->stopTrackingFirmwareVehicleTypeChanges();
2972}
2973
2975{
2976 if (_managerVehicle->isOfflineEditingVehicle()) {
2978 }
2979 if (_managerVehicle->armed() && _managerVehicle->flightMode() == _managerVehicle->missionFlightMode()) {
2981 }
2982 if (_controllerVehicle->firmwareType() != _managerVehicle->firmwareType() || QGCMAVLink::vehicleClass(_controllerVehicle->vehicleType()) != QGCMAVLink::vehicleClass(_managerVehicle->vehicleType())) {
2984 }
2986}
2987
2992
2994{
2995 if (_globalAltMode == QGroundControlQmlGlobal::AltitudeModeMixed) {
2997 } else {
2998 return _globalAltMode;
2999 }
3000}
3001
3003{
3004 if (_globalAltMode != altMode) {
3005 _globalAltMode = altMode;
3007 }
3008}
#define UPDATE_TIMEOUT
How often we check for bounding box changes.
QPair< VisualMissionItem *, VisualMissionItem * > VisualItemPair
QHash< VisualItemPair, FlightPathSegment * > FlightPathSegmentHashTable
#define qgcApp()
QString errorString
Error error
#define QGC_LOGGING_CATEGORY(name, categoryStr)
Application Settings.
Definition AppSettings.h:9
Fact *offlineEditingAscentSpeed READ offlineEditingAscentSpeed CONSTANT Fact * offlineEditingAscentSpeed()
Fact *offlineEditingCruiseSpeed READ offlineEditingCruiseSpeed CONSTANT Fact * offlineEditingCruiseSpeed()
Fact *offlineEditingHoverSpeed READ offlineEditingHoverSpeed CONSTANT Fact * offlineEditingHoverSpeed()
Fact *offlineEditingDescentSpeed READ offlineEditingDescentSpeed CONSTANT Fact * offlineEditingDescentSpeed()
Fact *offlineEditingFirmwareClass READ offlineEditingFirmwareClass CONSTANT Fact * offlineEditingFirmwareClass()
Fact *offlineEditingVehicleClass READ offlineEditingVehicleClass CONSTANT Fact * offlineEditingVehicleClass()
Fact *batteryPercentRemainingAnnounce READ batteryPercentRemainingAnnounce CONSTANT Fact * batteryPercentRemainingAnnounce()
Fact *defaultMissionItemAltitude READ defaultMissionItemAltitude CONSTANT Fact * defaultMissionItemAltitude()
void setSpecifyCameraMode(bool specifyCameraMode)
void setSpecifyGimbal(bool specifyGimbal)
bool specifyCameraMode(void) const
Fact * gimbalPitch(void)
Fact * cameraMode(void)
bool cameraModeSupported(void) const
Fact * gimbalYaw(void)
void isIncompleteChanged(void)
void boundingCubeChanged(void)
static constexpr const char * jsonComplexItemTypeKey
This mission item attribute specifies the type of the complex item.
virtual double minAMSLAltitude(void) const =0
void greatestDistanceToChanged(void)
bool isIncomplete(void) const
virtual double greatestDistanceTo(const QGeoCoordinate &other) const =0
virtual double complexDistance(void) const =0
void maxAMSLAltitudeChanged(void)
virtual double maxAMSLAltitude(void) const =0
void minAMSLAltitudeChanged(void)
void complexDistanceChanged(void)
bool load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString) final
static constexpr const char * jsonComplexItemTypeValue
void rawValueChanged(const QVariant &value)
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 ...
virtual QList< MAV_CMD > supportedMissionCommands(QGCMAVLink::VehicleClass_t) const
List of supported mission commands. Empty list for all commands supported.
virtual void batteryConsumptionData(Vehicle *vehicle, int &mAhBattery, double &hoverAmps, double &cruiseAmps) const
virtual bool sendHomePositionToVehicle() const
virtual bool hasGimbal(Vehicle *vehicle, bool &rollSupported, bool &pitchSupported, bool &yawSupported) const
static constexpr const char * jsonComplexItemTypeValue
static bool scanForItems(QmlObjectListModel *visualItems, bool flyView, PlanMasterController *masterController)
Scans the loaded items for a landing pattern complex item.
bool load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString) final
void terrainCollisionChanged(bool terrainCollision)
void totalDistanceChanged(double totalDistance)
void setCoordinate2(const QGeoCoordinate &coordinate)
void coord2AMSLAltChanged(void)
void coord1AMSLAltChanged(void)
void setSpecialVisual(bool specialVisual)
void amslTerrainHeightsChanged(void)
void setCoord2AMSLAlt(double alt)
void setCoord1AMSLAlt(double alt)
void setCoordinate1(const QGeoCoordinate &coordinate)
Used to convert a Plan to a KML document.
void addMission(Vehicle *vehicle, QmlObjectListModel *visualItems, QList< MissionItem * > rgMissionItems)
int lastSequenceNumber(void) const final
static MissionCommandTree * instance()
void minAMSLAltitudeChanged(double minAMSLAltitude)
void isROIActiveChanged(void)
void resumeMission(int resumeIndex)
double progressPct(void) const
bool showPlanFromManagerVehicle(void) final
void visualItemsChanged(void)
SendToVehiclePreCheckState sendToVehiclePreCheck(void)
void currentPlanViewVIIndexChanged(void)
bool dirty(void) const final
VisualMissionItem * insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int visualItemIndex, bool makeCurrentItem=false)
void isInsertTakeoffValidChanged(void)
void batteriesRequiredChanged(int batteriesRequired)
void isInsertLandValidChanged(void)
bool loadTextFile(QFile &file, QString &errorString)
void multipleLandPatternsAllowedChanged(void)
bool multipleLandPatternsAllowed(void) const
VisualMissionItem * insertTakeoffItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
QGeoCoordinate takeoffCoordinate()
QmlObjectListModel *visualItems READ visualItems NOTIFY visualItemsChanged(QmlObjectTreeModel *visualItemsTree READ visualItemsTree CONSTANT) 1(QPersistentModelIndex planFileGroupIndex READ planFileGroupIndex CONSTANT) 1(QPersistentModelIndex defaultsGroupIndex READ defaultsGroupIndex CONSTANT) 1(QPersistentModelIndex missionGroupIndex READ missionGroupIndex CONSTANT) 1(QPersistentModelIndex fenceGroupIndex READ fenceGroupIndex CONSTANT) 1(QPersistentModelIndex rallyGroupIndex READ rallyGroupIndex CONSTANT) 1(QmlObjectListModel *simpleFlightPathSegments READ simpleFlightPathSegments CONSTANT) 1(QmlObjectListModel *directionArrows READ directionArrows CONSTANT) 1(QStringList complexMissionItemNames READ complexMissionItemNames NOTIFY complexMissionItemNamesChanged) 1(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged) 1(QGeoCoordinate previousCoordinate MEMBER _previousCoordinate NOTIFY previousCoordinateChanged) 1(FlightPathSegment *splitSegment MEMBER _splitSegment NOTIFY splitSegmentChanged) 1(double progressPct READ progressPct NOTIFY progressPctChanged) 1(int missionItemCount READ missionItemCount NOTIFY missionItemCountChanged) 1(int currentMissionIndex READ currentMissionIndex NOTIFY currentMissionIndexChanged) 1(int resumeMissionIndex READ resumeMissionIndex NOTIFY resumeMissionIndexChanged) 1(int currentPlanViewSeqNum READ currentPlanViewSeqNum NOTIFY currentPlanViewSeqNumChanged) 1(int currentPlanViewVIIndex READ currentPlanViewVIIndex NOTIFY currentPlanViewVIIndexChanged) 1(VisualMissionItem *currentPlanViewItem READ currentPlanViewItem NOTIFY currentPlanViewItemChanged) 1(TakeoffMissionItem *takeoffMissionItem READ takeoffMissionItem NOTIFY takeoffMissionItemChanged) 1(double missionTotalDistance READ missionTotalDistance NOTIFY missionTotalDistanceChanged) 1(double missionPlannedDistance READ missionPlannedDistance NOTIFY missionPlannedDistanceChanged) 1(double missionTime READ missionTime NOTIFY missionTimeChanged) 1(double missionHoverDistance READ missionHoverDistance NOTIFY missionHoverDistanceChanged) 1(double missionCruiseDistance READ missionCruiseDistance NOTIFY missionCruiseDistanceChanged) 1(double missionHoverTime READ missionHoverTime NOTIFY missionHoverTimeChanged) 1(double missionCruiseTime READ missionCruiseTime NOTIFY missionCruiseTimeChanged) 1(double missionMaxTelemetry READ missionMaxTelemetry NOTIFY missionMaxTelemetryChanged) 1(int batteryChangePoint READ batteryChangePoint NOTIFY batteryChangePointChanged) 1(int batteriesRequired READ batteriesRequired NOTIFY batteriesRequiredChanged) 1(QGCGeoBoundingCube *travelBoundingCube READ travelBoundingCube NOTIFY missionBoundingCubeChanged) 1(QString surveyComplexItemName READ surveyComplexItemName CONSTANT) 1(QString corridorScanComplexItemName READ corridorScanComplexItemName CONSTANT) 1(QString structureScanComplexItemName READ structureScanComplexItemName CONSTANT) 1(bool onlyInsertTakeoffValid MEMBER _onlyInsertTakeoffValid NOTIFY onlyInsertTakeoffValidChanged) 1(bool isInsertTakeoffValid MEMBER _isInsertTakeoffValid NOTIFY isInsertTakeoffValidChanged) 1(bool isInsertLandValid MEMBER _isInsertLandValid NOTIFY isInsertLandValidChanged) 1(bool hasLandItem MEMBER _hasLandItem NOTIFY hasLandItemChanged) 1(bool multipleLandPatternsAllowed READ multipleLandPatternsAllowed NOTIFY multipleLandPatternsAllowedChanged) 1(bool isROIActive MEMBER _isROIActive NOTIFY isROIActiveChanged) 1(bool isROIBeginCurrentItem MEMBER _isROIBeginCurrentItem NOTIFY isROIBeginCurrentItemChanged) 1(bool flyThroughCommandsAllowed MEMBER _flyThroughCommandsAllowed NOTIFY flyThroughCommandsAllowedChanged) 1(double minAMSLAltitude MEMBER _minAMSLAltitude NOTIFY minAMSLAltitudeChanged) 1(double maxAMSLAltitude MEMBER _maxAMSLAltitude NOTIFY maxAMSLAltitudeChanged) 1(QGroundControlQmlGlobal in visualItemIndexForObject)(QObject *object) const
< Used by Plan view only for interactive editing
VisualMissionItem * insertLandItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
void offsetMission(double eastMeters, double northMeters, double upMeters=0.0, bool offsetTakeoffItems=false, bool offsetLandingItems=false)
void setCurrentPlanViewSeqNum(int sequenceNumber, bool force)
void maxAMSLAltitudeChanged(double maxAMSLAltitude)
void removeAllFromVehicle(void) final
void recalcTerrainProfile(void)
void missionPlannedDistanceChanged(double missionPlannedDistance)
void missionTotalDistanceChanged(double missionTotalDistance)
void hasLandItemChanged(void)
void _recalcFlightPathSegmentsSignal(void)
void complexMissionItemNamesChanged(void)
int currentMissionIndex(void) const
void missionMaxTelemetryChanged(double missionMaxTelemetry)
static void sendItemsToVehicle(Vehicle *vehicle, QmlObjectListModel *visualMissionItems)
Sends the mission items to the specified vehicle.
bool load(const QJsonObject &json, QString &errorString) final
void onlyInsertTakeoffValidChanged(void)
void splitSegmentChanged(void)
void repositionMission(const QGeoCoordinate &newHome, bool repositionTakeoffItems=true, bool repositionLandingItems=true)
void resumeMissionReady(void)
@ SendToVehiclePreCheckStateFirwmareVehicleMismatch
void batteryChangePointChanged(int batteryChangePoint)
void globalAltitudeModeChanged(void)
void rotateMission(double degreesCW, bool rotateTakeoffItems=false, bool rotateLandingItems=false)
void currentPlanViewSeqNumChanged(void)
void addMissionToKML(KMLPlanDomDocument &planKML)
void _recalcMissionFlightStatusSignal(void)
void flyThroughCommandsAllowedChanged(void)
void missionHoverDistanceChanged(double missionHoverDistance)
bool syncInProgress(void) const final
void sendToVehicle(void) final
void resumeMissionIndexChanged(void)
void currentMissionIndexChanged(int currentMissionIndex)
QGroundControlQmlGlobal::AltMode globalAltitudeMode(void)
VisualMissionItem * insertROIMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
void plannedHomePositionChanged(QGeoCoordinate plannedHomePosition)
bool isEmpty(void) const
QString surveyComplexItemName(void) const
void newItemsFromVehicle(void)
void save(QJsonObject &json) final
VisualMissionItem * insertSimpleMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
void missionHoverTimeChanged(void)
bool isFirstLandingComplexItem(const LandingComplexItem *item) const
QGeoCoordinate plannedHomePosition(void) const
QString corridorScanComplexItemName(void) const
QString structureScanComplexItemName(void) const
bool containsItems(void) const final
void progressPctChanged(double progressPct)
void isROIBeginCurrentItemChanged(void)
void missionCruiseTimeChanged(void)
QStringList complexMissionItemNames(void) const
QGroundControlQmlGlobal::AltMode globalAltitudeModeDefault(void)
int readyForSaveState(void) const
void currentPlanViewItemChanged(void)
void previousCoordinateChanged(void)
void removeAll(void) final
Removes all from controller only.
void setGlobalAltitudeMode(QGroundControlQmlGlobal::AltMode altMode)
void missionBoundingCubeChanged(void)
void missionTimeChanged(void)
void applyDefaultMissionAltitude(void)
Updates the altitudes of the items in the current mission to the new default altitude.
void setDirty(bool dirty) final
void start(bool flyView) final
Should be called immediately upon Component.onCompleted.
void missionCruiseDistanceChanged(double missionCruiseDistance)
void resumeMissionUploadFail(void)
void loadFromVehicle(void) final
VisualMissionItem * insertCancelROIMissionItem(int visualItemIndex, bool makeCurrentItem=false)
int resumeMissionIndex(void) const
void missionItemCountChanged(int missionItemCount)
VisualMissionItem * insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int visualItemIndex, bool makeCurrentItem=false)
QmlObjectListModel * visualItems(void)
void setParam1(double param1)
MAV_FRAME frame(void) const
Definition MissionItem.h:52
void save(QJsonObject &json) const
double param1(void) const
Definition MissionItem.h:54
QGeoCoordinate coordinate(void) const
int doJumpId(void) const
Definition MissionItem.h:62
int lastCurrentIndex(void) const
Last current mission item reported while in Mission flight mode.
void generateResumeMission(int resumeIndex)
int currentIndex(void) const
Current mission item as reported by MISSION_CURRENT.
void setInitialHomePositionFromUser(const QGeoCoordinate &coordinate)
bool scanForMissionSettings(QmlObjectListModel *visualItems, int scanIndex)
Scans the loaded items for settings items.
QGeoCoordinate coordinate(void) const final
void setCoordinate(const QGeoCoordinate &coordinate) final
void setInitialHomePosition(const QGeoCoordinate &coordinate)
bool addMissionEndAction(QList< MissionItem * > &items, int seqNum, QObject *missionItemParent)
CameraSection * cameraSection(void)
void endResetModel()
Depth-counted endResetModel — only the outermost call has effect.
void beginResetModel()
Depth-counted beginResetModel — only the outermost call has effect.
void dirtyChanged(bool dirty)
int count READ count NOTIFY countChanged(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) bool dirty() const
void syncInProgressChanged(bool syncInProgress)
PlanMasterController * _masterController
virtual void start(bool flyView)
Should be called immediately upon Component.onCompleted.
void dirtyChanged(bool dirty)
void resumeMissionUploadFail(void)
void currentIndexChanged(int currentIndex)
void lastCurrentIndexChanged(int lastCurrentIndex)
void sendComplete(bool error)
void resumeMissionReady(void)
void removeAll(void)
void newMissionItemsAvailable(bool removeAllRequested)
void loadFromVehicle(void)
void removeAllComplete(bool error)
void writeMissionItems(const QList< MissionItem * > &missionItems)
bool inProgress(void) const
void inProgressChanged(bool inProgress)
void progressPctChanged(double progressPercentPct)
const QList< MissionItem * > & missionItems(void)
Definition PlanManager.h:25
Master controller for mission, fence, rally.
Vehicle * controllerVehicle(void)
void managerVehicleChanged(Vehicle *managerVehicle)
RallyPointController * rallyPointController(void)
Fact *allowMultipleLandingPatterns READ allowMultipleLandingPatterns CONSTANT Fact * allowMultipleLandingPatterns()
Fact *showGimbalOnlyWhenSet READ showGimbalOnlyWhenSet CONSTANT Fact * showGimbalOnlyWhenSet()
Fact *takeoffItemNotRequired READ takeoffItemNotRequired CONSTANT Fact * takeoffItemNotRequired()
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
T value(int index) const
void setDirty(bool dirty) override final
QObject * get(int index)
QObject * removeAt(int index)
int count() const override final
void clear() override final
void clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
void insert(int index, QObject *object)
int indexOf(const QObject *object)
int rowCount(const QModelIndex &parent=QModelIndex()) const override
static constexpr int NodeTypeRole
QVariant data(const QModelIndex &index, int role=Qt::DisplayRole) const override
void removeChildren(const QModelIndex &parentIndex)
Removes all children of parentIndex without removing the parent itself.
QObject * removeItem(const QModelIndex &index)
QObject * removeAt(const QModelIndex &parentIndex, int row)
QModelIndex index(int row, int column, const QModelIndex &parent=QModelIndex()) const override
QModelIndex insertItem(int row, QObject *object, const QModelIndex &parentIndex=QModelIndex())
Inserts object at row under parentIndex. Returns the new item's index.
QModelIndex appendItem(QObject *object, const QModelIndex &parentIndex=QModelIndex())
Appends object as the last child of parentIndex (root if invalid). Returns the new item's index.
QmlObjectListModel * points(void)
Provides access to all app settings.
A SimpleMissionItem is used to represent a single MissionItem to the ui.
bool specifiesCoordinate(void) const final
void setSequenceNumber(int sequenceNumber) final
bool isStandaloneCoordinate(void) const final
int sequenceNumber(void) const final
QGroundControlQmlGlobal::AltMode altitudeMode(void) const
QGeoCoordinate entryCoordinate(void) const final
bool scanForSections(QmlObjectListModel *visualItems, int scanIndex, PlanMasterController *masterController)
double specifiedVehicleYaw(void) override
int lastSequenceNumber(void) const final
MAV_CMD mavCommand(void) const
bool specifiesAltitude(void) const
QGeoCoordinate coordinate(void) const final
void setAltitudeMode(QGroundControlQmlGlobal::AltMode altitudeMode)
virtual bool load(QTextStream &loadStream)
void setCoordinate(const QGeoCoordinate &coordinate) override
void setCommand(int command)
int command(void) const
MissionItem & missionItem(void)
int lastSequenceNumber(void) const final
bool load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString) final
static constexpr const char * jsonComplexItemTypeValue
static constexpr const char * jsonComplexItemTypeValue
bool load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString) final
static const QString name
static bool isTakeoffCommand(MAV_CMD command)
bool load(QTextStream &loadStream) final
int lastSequenceNumber(void) const final
int sequenceNumber(void) const final
static bool scanForItems(QmlObjectListModel *visualItems, bool flyView, PlanMasterController *masterController)
Scans the loaded items for a landing pattern complex item.
static constexpr const char * jsonComplexItemTypeValue
bool load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString) final
bool takeoffMissionCommand() const
bool px4Firmware() const
Definition Vehicle.h:495
void defaultHoverSpeedChanged(double hoverSpeed)
void defaultCruiseSpeedChanged(double cruiseSpeed)
QString missionFlightMode() const
Definition Vehicle.cc:3436
void _offlineVehicleTypeSettingChanged(QVariant varVehicleType)
Definition Vehicle.cc:433
QString flightMode() const
Definition Vehicle.cc:1549
bool vtol() const
Definition Vehicle.cc:1869
bool rover() const
Definition Vehicle.cc:1849
bool multiRotor() const
Definition Vehicle.cc:1864
MAV_TYPE vehicleType() const
Definition Vehicle.h:428
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
Definition Vehicle.h:444
bool isOfflineEditingVehicle() const
Definition Vehicle.h:508
MAV_AUTOPILOT firmwareType() const
Definition Vehicle.h:427
void _offlineFirmwareTypeSettingChanged(QVariant varFirmwareType)
Definition Vehicle.cc:420
void trackFirmwareVehicleTypeChanges(void)
Definition Vehicle.cc:214
double defaultHoverSpeed() const
Definition Vehicle.h:525
void stopTrackingFirmwareVehicleTypeChanges(void)
Definition Vehicle.cc:223
bool initialPlanRequestComplete() const
Definition Vehicle.h:744
bool fixedWing() const
Definition Vehicle.cc:1844
double defaultCruiseSpeed() const
Definition Vehicle.h:524
bool armed() const
Definition Vehicle.h:449
VehicleSupports * supports()
Definition Vehicle.h:405
MissionManager * missionManager()
Definition Vehicle.h:575
void vehicleTypeChanged()
virtual int lastSequenceNumber(void) const =0
void setIsCurrentItem(bool isCurrentItem)
void setDistanceFromStart(double distanceFromStart)
void setHasCurrentChildItem(bool hasCurrentChildItem)
void specifiedVehicleYawChanged(void)
virtual void setCoordinate(const QGeoCoordinate &coordinate)=0
virtual int sequenceNumber(void) const =0
void setTerrainCollision(bool terrainCollision)
virtual void applyNewAltitude(double newAltitude)=0
Adjust the altitude of the item if appropriate to the new altitude.
void setAltDifference(double altDifference)
void setMissionVehicleYaw(double vehicleYaw)
static constexpr const char * jsonTypeComplexItemValue
Item type is Complex Item.
virtual bool isTakeoffItem(void) const
virtual bool isStandaloneCoordinate(void) const =0
void amslExitAltChanged(double alt)
virtual double amslExitAlt(void) const =0
void setParentItem(VisualMissionItem *parentItem)
void terrainAltitudeChanged(double terrainAltitude)
void setWizardMode(bool wizardMode)
bool isCurrentItem(void) const
void lastSequenceNumberChanged(int sequenceNumber)
void entryCoordinateChanged(const QGeoCoordinate &entryCoordinate)
void specifiesCoordinateChanged(void)
void coordinateChanged(const QGeoCoordinate &coordinate)
void setSimpleFlighPathSegment(FlightPathSegment *segment)
virtual double specifiedGimbalPitch(void)=0
void specifiedFlightSpeedChanged(void)
void clearSimpleFlighPathSegment(void)
void currentVTOLModeChanged(void)
Signals that this item has changed the VTOL mode (MAV_CMD_DO_VTOL_TRANSITION)
void setDistance(double distance)
virtual void setSequenceNumber(int sequenceNumber)=0
virtual double specifiedGimbalYaw(void)=0
virtual double specifiedFlightSpeed(void)=0
virtual double amslEntryAlt(void) const =0
void setAltPercent(double altPercent)
virtual ReadyForSaveState readyForSaveState(void) const
void specifiedGimbalYawChanged(void)
void amslEntryAltChanged(double alt)
void specifiedGimbalPitchChanged(void)
void setTerrainPercent(double terrainPercent)
virtual void setMissionFlightStatus(MissionController::MissionFlightStatus_t &missionFlightStatus)
static constexpr const char * jsonTypeKey
Json file attribute which specifies the item type.
virtual QGeoCoordinate coordinate(void) const =0
virtual bool specifiesAltitudeOnly(void) const =0
virtual void appendMissionItems(QList< MissionItem * > &items, QObject *missionItemParent)=0
virtual QString commandName(void) const =0
virtual bool isLandCommand(void) const
static constexpr const char * jsonTypeSimpleItemValue
Item type is MISSION_ITEM.
virtual QGCGeoBoundingCube * boundingCube(void)
virtual bool isSimpleItem(void) const =0
QmlObjectListModel * childItems(void)
virtual double additionalTimeDelay(void) const =0
virtual bool specifiesCoordinate(void) const =0
void exitCoordinateChanged(const QGeoCoordinate &exitCoordinate)
void setAzimuth(double azimuth)
void additionalTimeDelayChanged(void)
virtual void save(QJsonArray &missionItems)=0
virtual QGeoCoordinate exitCoordinate(void) const =0
VisualMissionItem * parentItem(void)
virtual QGeoCoordinate entryCoordinate(void) const =0
double terrainAltitude(void) const
virtual double editableAlt(void) const =0
bool validateExternalQGCJsonFile(const QJsonObject &jsonObject, const QString &expectedFileType, int minSupportedVersion, int maxSupportedVersion, int &version, QString &errorString)
returned error string if validation fails
constexpr const char * jsonVersionKey
Definition JsonHelper.h:109
bool validateKeys(const QJsonObject &jsonObject, const QList< KeyValidateInfo > &keyInfo, QString &errorString)
void saveGeoCoordinate(const QGeoCoordinate &coordinate, bool writeAltitude, QJsonValue &jsonValue, bool geoJsonFormat=false)
bool loadGeoCoordinate(const QJsonValue &jsonValue, bool altitudeRequired, QGeoCoordinate &coordinate, QString &errorString, bool geoJsonFormat=false)
if true, use [lon, lat], [lat, lon] 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 hoverAmpsTotal
Total hover amps used.
double gimbalPitch
NaN signals pitch was never changed.
QGCMAVLink::VehicleClass_t vtolMode
Either VehicleClassFixedWing, VehicleClassMultiRotor, VehicleClassGeneric (mode unknown)
int batteryChangePoint
-1 for not supported, 0 for not needed
double cruiseAmps
Amp consumption during cruise.
double ampMinutesAvailable
Amp minutes available from single battery.
double cruiseAmpsTotal
Total cruise amps used.
double gimbalYaw
NaN signals yaw was never changed.
double hoverAmps
Amp consumption during hover.