QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MissionController.cc
Go to the documentation of this file.
2#include "MissionController.h"
3#include "Vehicle.h"
4#include "VehicleSupports.h"
5#include "MissionManager.h"
6#include "FlightPathSegment.h"
7#include "FirmwarePlugin.h"
8#include "QGCApplication.h"
9#include "SimpleMissionItem.h"
10#include "SurveyComplexItem.h"
15#include "GeoJsonHelper.h"
16#include "JsonParsing.h"
18#include "SettingsManager.h"
19#include "AppSettings.h"
20#include "MissionSettingsItem.h"
22#include "KMLPlanDomDocument.h"
23#include "QGCCorePlugin.h"
24#include "TakeoffMissionItem.h"
25#include "PlanViewSettings.h"
26#include "MissionCommandTree.h"
27#include "QGCMath.h"
28#include "QGCLoggingCategory.h"
29
30#include <QtCore/QJsonArray>
31#include <QtCore/QJsonDocument>
32#include <QtMath>
33
34#define UPDATE_TIMEOUT 5000
35
36QGC_LOGGING_CATEGORY(MissionControllerLog, "PlanManager.MissionController")
37
38MissionController::MissionController(PlanMasterController* masterController, QObject *parent)
39 : PlanElementController (masterController, parent)
40 , _controllerVehicle (masterController->controllerVehicle())
41 , _managerVehicle (masterController->managerVehicle())
42 , _missionManager (masterController->managerVehicle()->missionManager())
43 , _visualItems (new QmlObjectListModel(this))
44 , _planViewSettings (SettingsManager::instance()->planViewSettings())
45 , _appSettings (SettingsManager::instance()->appSettings())
46{
47 _resetMissionFlightStatus();
48
49 _updateTimer.setSingleShot(true);
50
51 connect(&_updateTimer, &QTimer::timeout, this, &MissionController::_updateTimeout);
52 connect(_planViewSettings->takeoffItemNotRequired(), &Fact::rawValueChanged, this, &MissionController::_forceRecalcOfAllowedBits);
53 connect(_planViewSettings->allowMultipleLandingPatterns(), &Fact::rawValueChanged, this, &MissionController::multipleLandPatternsAllowedChanged);
55 connect(this, &MissionController::multipleLandPatternsAllowedChanged, this, &MissionController::_forceRecalcOfAllowedBits);
57
58 // The follow is used to compress multiple recalc calls in a row to into a single call.
59 connect(this, &MissionController::_recalcMissionFlightStatusSignal, this, &MissionController::_recalcMissionFlightStatus, Qt::QueuedConnection);
60 connect(this, &MissionController::_recalcFlightPathSegmentsSignal, this, &MissionController::_recalcFlightPathSegments, Qt::QueuedConnection);
61 qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(&MissionController::_recalcMissionFlightStatusSignal));
62 qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(&MissionController::_recalcFlightPathSegmentsSignal));
63 qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(&MissionController::recalcTerrainProfile));
64}
65
70
71void MissionController::_resetMissionFlightStatus(void)
72{
73 _flightStatusCalc.reset(_controllerVehicle, _managerVehicle, _missionContainsVTOLTakeoff);
74 _missionFlightStatus = _flightStatusCalc.status();
75
76 emit missionPlannedDistanceChanged(_missionFlightStatus.plannedDistance);
77 emit missionTimeChanged();
78 emit missionHoverDistanceChanged(_missionFlightStatus.hoverDistance);
79 emit missionCruiseDistanceChanged(_missionFlightStatus.cruiseDistance);
82 emit missionMaxTelemetryChanged(_missionFlightStatus.maxTelemetryDistance);
83 emit batteryChangePointChanged(_missionFlightStatus.batteryChangePoint);
84 emit batteriesRequiredChanged(_missionFlightStatus.batteriesRequired);
85}
86
87void MissionController::start(bool flyView)
88{
89 qCDebug(MissionControllerLog) << "start flyView" << flyView;
90
91 _managerVehicleChanged(_managerVehicle);
92 connect(_masterController, &PlanMasterController::managerVehicleChanged, this, &MissionController::_managerVehicleChanged);
93
95 _init();
96}
97
98void MissionController::_init(void)
99{
100 // We start with an empty mission
101 _addMissionSettings(_visualItems);
102
103 // Set up the tree model structure once (groups + static children)
104 _setupTreeModel();
105
106 _initAllVisualItems();
107}
108
109// Called when new mission items have completed downloading from Vehicle
110void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllRequested)
111{
112 qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle flyView:count" << _flyView << _missionManager->missionItems().count();
113
114 // Fly view always reloads on _loadComplete
115 // Plan view only reloads if:
116 // - Load was specifically requested
117 // - There is no current Plan
118 if (_flyView || removeAllRequested || _itemsRequested || isEmpty()) {
119 // Fly Mode (accept if):
120 // - Always accepts new items from the vehicle so Fly view is kept up to date
121 // Edit Mode (accept if):
122 // - Remove all was requested from Fly view (clear mission on flight end)
123 // - A load from vehicle was manually requested
124 // - The initial automatic load from a vehicle completed and the current editor is empty
125
126 _setupNewVisualItems();
127
128 const QList<MissionItem*>& newMissionItems = _missionManager->missionItems();
129 qCDebug(MissionControllerLog) << "loading from vehicle: count"<< newMissionItems.count();
130
131 int i=0;
132 if (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() && newMissionItems.count() != 0) {
133 // First item is fake home position
134 MissionItem* fakeHomeItem = newMissionItems[0];
135 if (fakeHomeItem->coordinate().latitude() != 0 || fakeHomeItem->coordinate().longitude() != 0) {
136 _settingsItem->setCoordinate(fakeHomeItem->coordinate());
137 }
138 i = 1;
139 }
140
141 bool weHaveItemsFromVehicle = false;
142 for (; i < newMissionItems.count(); i++) {
143 weHaveItemsFromVehicle = true;
144 const MissionItem* missionItem = newMissionItems[i];
145 SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, _flyView, *missionItem);
146 if (TakeoffMissionItem::isTakeoffCommand(static_cast<MAV_CMD>(simpleItem->command()))) {
147 // This needs to be a TakeoffMissionItem
148 _takeoffMissionItem = new TakeoffMissionItem(*missionItem, _masterController, _flyView, _settingsItem, false /* forLoad */);
149 _takeoffMissionItem->setWizardMode(false);
150 simpleItem->deleteLater();
151 simpleItem = _takeoffMissionItem;
152 }
153 _visualItems->append(simpleItem);
154 }
155
156 // We set Altitude frame to mixed, otherwise if we need a non relative altitude frame we won't be able to change it
157 setGlobalAltitudeFrame(weHaveItemsFromVehicle ? QGroundControlQmlGlobal::AltitudeFrameMixed : QGroundControlQmlGlobal::AltitudeFrameRelative);
158
159 MissionController::_scanForAdditionalSettings(_visualItems, _masterController);
160
161 _initAllVisualItems();
162
163 emit newItemsFromVehicle();
164
166 }
167 _itemsRequested = false;
168}
169
171{
172 if (_masterController->offline()) {
173 qCCritical(MissionControllerLog) << "MissionControllerLog::loadFromVehicle called while offline";
174 } else if (syncInProgress()) {
175 qCCritical(MissionControllerLog) << "MissionControllerLog::loadFromVehicle called while syncInProgress";
176 } else {
177 _itemsRequested = true;
178 _managerVehicle->missionManager()->loadFromVehicle();
179 }
180}
181
183{
184 if (_masterController->offline()) {
185 qCCritical(MissionControllerLog) << "MissionControllerLog::sendToVehicle called while offline";
186 } else if (syncInProgress()) {
187 qCCritical(MissionControllerLog) << "MissionControllerLog::sendToVehicle called while syncInProgress";
188 } else {
189 qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
190 if (_visualItems->count() == 1) {
191 // This prevents us from sending a possibly bogus home position to the vehicle
192 QmlObjectListModel emptyModel;
193 sendItemsToVehicle(_managerVehicle, &emptyModel);
194 } else {
195 sendItemsToVehicle(_managerVehicle, _visualItems);
196 }
197 setDirty(false);
198 }
199}
200
204bool MissionController::_convertToMissionItems(QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent)
205{
206 if (visualMissionItems->count() == 0) {
207 return false;
208 }
209
210 bool endActionSet = false;
211 int lastSeqNum = 0;
212
213 for (int i=0; i<visualMissionItems->count(); i++) {
214 VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(visualMissionItems->get(i));
215
216 lastSeqNum = visualItem->lastSequenceNumber();
217 visualItem->appendMissionItems(rgMissionItems, missionItemParent);
218
219 qCDebug(MissionControllerLog) << "_convertToMissionItems seqNum:lastSeqNum:command"
220 << visualItem->sequenceNumber()
221 << lastSeqNum
222 << visualItem->commandName();
223 }
224
225 // Mission settings has a special case for end mission action
226 MissionSettingsItem* settingsItem = visualMissionItems->value<MissionSettingsItem*>(0);
227 if (settingsItem) {
228 endActionSet = settingsItem->addMissionEndAction(rgMissionItems, lastSeqNum + 1, missionItemParent);
229 }
230
231 return endActionSet;
232}
233
235{
236 QObject* deleteParent = new QObject();
237 QList<MissionItem*> rgMissionItems;
238
239 _convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
240 planKML.addMission(_controllerVehicle, _visualItems, rgMissionItems);
241 deleteParent->deleteLater();
242}
243
245{
246 if (vehicle) {
247 QList<MissionItem*> rgMissionItems;
248
249 _convertToMissionItems(visualMissionItems, rgMissionItems, vehicle);
250
251 // PlanManager takes control of MissionItems so no need to delete
252 vehicle->missionManager()->writeMissionItems(rgMissionItems);
253 }
254}
255
256int MissionController::_nextSequenceNumber(void)
257{
258 if (_visualItems->count() == 0) {
259 qWarning() << "Internal error: Empty visual item list";
260 return 0;
261 } else {
262 VisualMissionItem* lastItem = _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1);
263 return lastItem->lastSequenceNumber() + 1;
264 }
265}
266
267VisualMissionItem* MissionController::_insertSimpleMissionItemWorker(QGeoCoordinate coordinate, MAV_CMD command, int visualItemIndex, bool makeCurrentItem)
268{
269 int sequenceNumber = _nextSequenceNumber();
270 SimpleMissionItem * newItem = new SimpleMissionItem(_masterController, _flyView, false /* forLoad */);
271 newItem->setSequenceNumber(sequenceNumber);
272 newItem->setCoordinate(coordinate);
273 newItem->setCommand(command);
274 _initVisualItem(newItem);
275
276 if (newItem->specifiesAltitude()) {
277 if (!MissionCommandTree::instance()->isLandCommand(command)) {
278 double prevAltitude;
280
281 if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltFrame)) {
282 newItem->altitude()->setRawValue(prevAltitude);
284 // We are in mixed altitude frames, so copy from previous. Otherwise altitude frame will be set from global setting.
285 newItem->setAltitudeFrame(static_cast<QGroundControlQmlGlobal::AltitudeFrame>(prevAltFrame));
286 }
287 }
288 }
289 }
290 if (visualItemIndex == -1) {
291 _visualItems->append(newItem);
292 } else {
293 _visualItems->insert(visualItemIndex, newItem);
294 }
295
296 // We send the click coordinate through here to be able to set the planned home position from the user click location if needed
297 _recalcAllWithCoordinate(coordinate);
298
299 if (makeCurrentItem) {
301 }
302
303 _firstItemAdded();
304
305 return newItem;
306}
307
308
309VisualMissionItem* MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem)
310{
311 return _insertSimpleMissionItemWorker(coordinate, MAV_CMD_NAV_WAYPOINT, visualItemIndex, makeCurrentItem);
312}
313
314VisualMissionItem* MissionController::insertTakeoffItem(QGeoCoordinate /*coordinate*/, int visualItemIndex, bool makeCurrentItem)
315{
316 int sequenceNumber = _nextSequenceNumber();
317 _takeoffMissionItem = new TakeoffMissionItem(_controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF, _masterController, _flyView, _settingsItem, false /* forLoad */);
318 _takeoffMissionItem->setSequenceNumber(sequenceNumber);
319 _initVisualItem(_takeoffMissionItem);
320
321 if (_takeoffMissionItem->specifiesAltitude()) {
322 double prevAltitude;
324
325 if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltFrame)) {
326 _takeoffMissionItem->altitude()->setRawValue(prevAltitude);
327 _takeoffMissionItem->setAltitudeFrame(static_cast<QGroundControlQmlGlobal::AltitudeFrame>(prevAltFrame));
328 }
329 }
330 if (visualItemIndex == -1) {
331 _visualItems->append(_takeoffMissionItem);
332 } else {
333 _visualItems->insert(visualItemIndex, _takeoffMissionItem);
334 }
335
336 _recalcAll();
337
338 if (makeCurrentItem) {
339 setCurrentPlanViewSeqNum(_takeoffMissionItem->sequenceNumber(), true);
340 }
341
342 _firstItemAdded();
343
344 return _takeoffMissionItem;
345}
346
348 // Can't have more than one land sequence unless allowed in settings and
349 // supported by the firmware
350 return _planViewSettings->allowMultipleLandingPatterns()
351 ->rawValue().toBool() &&
353}
354
355VisualMissionItem* MissionController::insertLandItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem)
356{
357 if (_controllerVehicle->fixedWing()) {
358 FixedWingLandingComplexItem* fwLanding = qobject_cast<FixedWingLandingComplexItem*>(insertComplexMissionItem(FixedWingLandingComplexItem::canonicalName, coordinate, visualItemIndex, makeCurrentItem));
359 return fwLanding;
360 } else if (_controllerVehicle->vtol()) {
361 VTOLLandingComplexItem* vtolLanding = qobject_cast<VTOLLandingComplexItem*>(insertComplexMissionItem(VTOLLandingComplexItem::canonicalName, coordinate, visualItemIndex, makeCurrentItem));
362 return vtolLanding;
363 } else {
364 return _insertSimpleMissionItemWorker(coordinate, _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_RETURN_TO_LAUNCH, visualItemIndex, makeCurrentItem);
365 }
366}
367
368VisualMissionItem* MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem)
369{
370 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_insertSimpleMissionItemWorker(coordinate, MAV_CMD_DO_SET_ROI_LOCATION, visualItemIndex, makeCurrentItem));
371
372 if (!_controllerVehicle->firmwarePlugin()->supportedMissionCommands(QGCMAVLink::VehicleClassGeneric).contains(MAV_CMD_DO_SET_ROI_LOCATION)) {
373 simpleItem->setCommand(MAV_CMD_DO_SET_ROI) ;
374 simpleItem->missionItem().setParam1(MAV_ROI_LOCATION);
375 }
376 return simpleItem;
377}
378
379VisualMissionItem* MissionController::insertCancelROIMissionItem(int visualItemIndex, bool makeCurrentItem)
380{
381 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_insertSimpleMissionItemWorker(QGeoCoordinate(), MAV_CMD_DO_SET_ROI_NONE, visualItemIndex, makeCurrentItem));
382
383 if (!_controllerVehicle->firmwarePlugin()->supportedMissionCommands(QGCMAVLink::VehicleClassGeneric).contains(MAV_CMD_DO_SET_ROI_NONE)) {
384 simpleItem->setCommand(MAV_CMD_DO_SET_ROI) ;
385 simpleItem->missionItem().setParam1(MAV_ROI_NONE);
386 }
387 return simpleItem;
388}
389
390VisualMissionItem* MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int visualItemIndex, bool makeCurrentItem)
391{
393 if (!newItem) {
394 return nullptr;
395 }
396 newItem->setCoordinate(mapCenterCoordinate);
397
399 double prevAltitude;
401 if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltFrame)) {
402 newItem->applyPreviousAltitudeFrame(prevAltFrame, prevAltitude);
403 }
404 }
405
406 _insertComplexMissionItemWorker(mapCenterCoordinate, newItem, visualItemIndex, makeCurrentItem);
407
408 return newItem;
409}
410
411VisualMissionItem* MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int visualItemIndex, bool makeCurrentItem)
412{
414 if (!newItem) {
415 return nullptr;
416 }
417
418 _insertComplexMissionItemWorker(QGeoCoordinate(), newItem, visualItemIndex, makeCurrentItem);
419
420 return newItem;
421}
422
423void MissionController::_insertComplexMissionItemWorker(const QGeoCoordinate& mapCenterCoordinate, ComplexMissionItem* complexItem, int visualItemIndex, bool makeCurrentItem)
424{
425 int sequenceNumber = _nextSequenceNumber();
426 bool surveyStyleItem = qobject_cast<SurveyComplexItem*>(complexItem) ||
427 qobject_cast<CorridorScanComplexItem*>(complexItem) ||
428 qobject_cast<StructureScanComplexItem*>(complexItem);
429
430 if (surveyStyleItem) {
431 bool rollSupported = false;
432 bool pitchSupported = false;
433 bool yawSupported = false;
434
435 // If the vehicle is known to have a gimbal then we automatically point the gimbal straight down if not already set
436
437 MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
438 CameraSection* cameraSection = settingsItem->cameraSection();
439
440 // Set camera to photo mode (leave alone if user already specified)
441 if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
442 cameraSection->setSpecifyCameraMode(true);
443 cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
444 }
445
446 // Point gimbal straight down
447 if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
448 // If the user already specified a gimbal angle leave it alone
449 if (!cameraSection->specifyGimbal()) {
450 cameraSection->setSpecifyGimbal(true);
451 cameraSection->gimbalPitch()->setRawValue(-90.0);
452 }
453 }
454 }
455
456 complexItem->setSequenceNumber(sequenceNumber);
457 if (!qobject_cast<VTOLLandingComplexItem*>(complexItem)) {
458 complexItem->setWizardMode(true);
459 }
460 _initVisualItem(complexItem);
461
462 if (visualItemIndex == -1) {
463 _visualItems->append(complexItem);
464 } else {
465 _visualItems->insert(visualItemIndex, complexItem);
466 }
467
468 //-- Keep track of bounding box changes in complex items
469 if(!complexItem->isSimpleItem()) {
470 connect(complexItem, &ComplexMissionItem::boundingCubeChanged, this, &MissionController::_complexBoundingBoxChanged);
471 }
472 _recalcAllWithCoordinate(mapCenterCoordinate);
473
474 if (makeCurrentItem) {
475 setCurrentPlanViewSeqNum(complexItem->sequenceNumber(), true);
476 }
477 _firstItemAdded();
478}
479
481{
482 return _visualItems ? _visualItems->indexOf(object) : -1;
483}
484
486{
487 if (viIndex <= 0 || viIndex >= _visualItems->count()) {
488 qWarning() << "MissionController::removeVisualItem called with bad index - count:index" << _visualItems->count() << viIndex;
489 return;
490 }
491
492 bool removeSurveyStyle = _visualItems->value<SurveyComplexItem*>(viIndex) || _visualItems->value<CorridorScanComplexItem*>(viIndex);
493 VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->removeAt(viIndex));
494
495 if (item == _takeoffMissionItem) {
496 _takeoffMissionItem = nullptr;
497 }
498
499 _deinitVisualItem(item);
500 item->deleteLater();
501
502 if (removeSurveyStyle) {
503 // Determine if the mission still has another survey style item in it
504 bool foundSurvey = false;
505 for (int i=1; i<_visualItems->count(); i++) {
506 if (_visualItems->value<SurveyComplexItem*>(i) || _visualItems->value<CorridorScanComplexItem*>(i)) {
507 foundSurvey = true;
508 break;
509 }
510 }
511
512 // If there is no longer a survey item in the mission remove added commands
513 if (!foundSurvey) {
514 bool rollSupported = false;
515 bool pitchSupported = false;
516 bool yawSupported = false;
517 CameraSection* cameraSection = _settingsItem->cameraSection();
518 if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
519 if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
520 cameraSection->setSpecifyGimbal(false);
521 }
522 }
523 if (cameraSection->cameraModeSupported() && cameraSection->specifyCameraMode() && cameraSection->cameraMode()->rawValue().toInt() == 0) {
524 cameraSection->setSpecifyCameraMode(false);
525 }
526 }
527 }
528
529 _recalcAll();
530
531 // Adjust current item
532 int newVIIndex;
533 if (viIndex >= _visualItems->count()) {
534 newVIIndex = _visualItems->count() - 1;
535 } else {
536 newVIIndex = viIndex;
537 }
538 setCurrentPlanViewSeqNum(_visualItems->value<VisualMissionItem*>(newVIIndex)->sequenceNumber(), true);
539
540 setDirty(true);
541
542 if (_visualItems->count() == 1) {
543 _allItemsRemoved();
544 }
545}
546
547void MissionController::_setupNewVisualItems(QmlObjectListModel* newItems)
548{
549 QmlObjectListModel* oldItems = _visualItems;
550
551 if (oldItems) {
552 _deinitAllVisualItems();
553
554 // Destroy old items after a delay — TreeView delegates are torn down
555 // asynchronously during a polish cycle and may still hold bindings.
556 QTimer::singleShot(1000, oldItems, [oldItems] {
557 oldItems->clearAndDeleteContents();
558 oldItems->deleteLater();
559 });
560 }
561
562 _settingsItem = nullptr;
563 _takeoffMissionItem = nullptr;
564
565 if (newItems) {
566 _visualItems = newItems;
567 if (_visualItems->count() == 0) {
568 _addMissionSettings(_visualItems);
569 } else {
570 _settingsItem = _visualItems->value<MissionSettingsItem*>(0);
571 }
572 } else {
573 _visualItems = new QmlObjectListModel(this);
574 _addMissionSettings(_visualItems);
575 }
576}
577
579{
580 _setupNewVisualItems();
581 _initAllVisualItems();
582 setDirty(true);
583 _resetMissionFlightStatus();
584 _allItemsRemoved();
585}
586
587bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString)
588{
589 // Validate root object keys
590 QList<JsonParsing::KeyValidateInfo> rootKeyInfoList = {
591 { _jsonPlannedHomePositionKey, QJsonValue::Array, true },
592 { _jsonItemsKey, QJsonValue::Array, true },
593 { _jsonFirmwareTypeKey, QJsonValue::Double, true },
594 { _jsonVehicleTypeKey, QJsonValue::Double, false },
595 { _jsonCruiseSpeedKey, QJsonValue::Double, false },
596 { _jsonHoverSpeedKey, QJsonValue::Double, false },
597 { _jsonGlobalPlanAltitudeModeKey, QJsonValue::Double, false },
598 };
599 if (!JsonParsing::validateKeys(json, rootKeyInfoList, errorString)) {
600 return false;
601 }
602
604
605 qCDebug(MissionControllerLog) << "MissionController::_loadJsonMissionFileV2 itemCount:" << json[_jsonItemsKey].toArray().count();
606
608
609 // Get the firmware/vehicle type from the plan file
610 MAV_AUTOPILOT planFileFirmwareType = static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt());
611 MAV_TYPE planFileVehicleType = static_cast<MAV_TYPE> (QGCMAVLink::vehicleClassToMavType(appSettings->offlineEditingVehicleClass()->rawValue().toInt()));
612 if (json.contains(_jsonVehicleTypeKey)) {
613 planFileVehicleType = static_cast<MAV_TYPE>(json[_jsonVehicleTypeKey].toInt());
614 }
615
616 // Update firmware/vehicle offline settings if we aren't connect to a vehicle
617 if (_masterController->offline()) {
618 appSettings->offlineEditingFirmwareClass()->setRawValue(QGCMAVLink::firmwareClass(static_cast<MAV_AUTOPILOT>(json[_jsonFirmwareTypeKey].toInt())));
619 if (json.contains(_jsonVehicleTypeKey)) {
620 appSettings->offlineEditingVehicleClass()->setRawValue(QGCMAVLink::vehicleClass(planFileVehicleType));
621 }
622 }
623
624 // The controller vehicle always tracks the Plan file firmware/vehicle types so update it
625 _controllerVehicle->stopTrackingFirmwareVehicleTypeChanges();
626 _controllerVehicle->_offlineFirmwareTypeSettingChanged(planFileFirmwareType);
627 _controllerVehicle->_offlineVehicleTypeSettingChanged(planFileVehicleType);
628
629 if (json.contains(_jsonCruiseSpeedKey)) {
630 appSettings->offlineEditingCruiseSpeed()->setRawValue(json[_jsonCruiseSpeedKey].toDouble());
631 }
632 if (json.contains(_jsonHoverSpeedKey)) {
633 appSettings->offlineEditingHoverSpeed()->setRawValue(json[_jsonHoverSpeedKey].toDouble());
634 }
635 if (json.contains(_jsonGlobalPlanAltitudeModeKey)) {
636 setGlobalAltitudeFrame(json[_jsonGlobalPlanAltitudeModeKey].toVariant().value<QGroundControlQmlGlobal::AltitudeFrame>());
637 }
638
639 QGeoCoordinate homeCoordinate;
640 if (!GeoJsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
641 return false;
642 }
644 settingsItem->setCoordinate(homeCoordinate);
645 visualItems->insert(0, settingsItem);
646 qCDebug(MissionControllerLog) << "plannedHomePosition" << homeCoordinate;
647
648 // Read mission items
649
650 int nextSequenceNumber = 1; // Start with 1 since home is in 0
651 const QJsonArray rgMissionItems(json[_jsonItemsKey].toArray());
652 for (int i=0; i<rgMissionItems.count(); i++) {
653 // Convert to QJsonObject
654 const QJsonValue& itemValue = rgMissionItems[i];
655 if (!itemValue.isObject()) {
656 errorString = tr("Mission item %1 is not an object").arg(i);
657 return false;
658 }
659 const QJsonObject itemObject = itemValue.toObject();
660
661 // Load item based on type
662
663 QList<JsonParsing::KeyValidateInfo> itemKeyInfoList = {
664 { VisualMissionItem::jsonTypeKey, QJsonValue::String, true },
665 };
666 if (!JsonParsing::validateKeys(itemObject, itemKeyInfoList, errorString)) {
667 return false;
668 }
669 QString itemType = itemObject[VisualMissionItem::jsonTypeKey].toString();
670
672 SimpleMissionItem* simpleItem = new SimpleMissionItem(_masterController, _flyView, true /* forLoad */);
673 if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
674 if (TakeoffMissionItem::isTakeoffCommand(static_cast<MAV_CMD>(simpleItem->command()))) {
675 // This needs to be a TakeoffMissionItem
676 TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_masterController, _flyView, settingsItem, true /* forLoad */);
677 takeoffItem->load(itemObject, nextSequenceNumber, errorString);
678 simpleItem->deleteLater();
679 simpleItem = takeoffItem;
680 }
681 qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
682 nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
683 visualItems->append(simpleItem);
684 } else {
685 return false;
686 }
687 } else if (itemType == VisualMissionItem::jsonTypeComplexItemValue) {
688 QList<JsonParsing::KeyValidateInfo> complexItemKeyInfoList = {
689 { ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true },
690 };
691 if (!JsonParsing::validateKeys(itemObject, complexItemKeyInfoList, errorString)) {
692 return false;
693 }
694 QString complexItemType = itemObject[ComplexMissionItem::jsonComplexItemTypeKey].toString();
695
696 qCDebug(MissionControllerLog) << "Loading complex item type:" << complexItemType << "nextSequenceNumber:" << nextSequenceNumber;
698 if (!complexItem) {
699 errorString = tr("Unsupported complex item type: %1").arg(complexItemType);
700 return false;
701 }
702 if (!complexItem->load(itemObject, nextSequenceNumber++, errorString)) {
703 delete complexItem;
704 return false;
705 }
706 nextSequenceNumber = complexItem->lastSequenceNumber() + 1;
707 qCDebug(MissionControllerLog) << "Complex item load complete nextSequenceNumber:" << nextSequenceNumber;
708 visualItems->append(complexItem);
709 } else {
710 errorString = tr("Unknown item type: %1").arg(itemType);
711 return false;
712 }
713 }
714
715 // Fix up the DO_JUMP commands jump sequence number by finding the item with the matching doJumpId
716 for (int i=0; i<visualItems->count(); i++) {
719 if (doJumpItem->command() == MAV_CMD_DO_JUMP) {
720 bool found = false;
721 int findDoJumpId = static_cast<int>(doJumpItem->missionItem().param1());
722 for (int j=0; j<visualItems->count(); j++) {
725 if (targetItem->missionItem().doJumpId() == findDoJumpId) {
726 doJumpItem->missionItem().setParam1(targetItem->sequenceNumber());
727 found = true;
728 break;
729 }
730 }
731 }
732 if (!found) {
733 errorString = tr("Could not find doJumpId: %1").arg(findDoJumpId);
734 return false;
735 }
736 }
737 }
738 }
739
740 return true;
741}
742
743bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString)
744{
745 bool firstItem = true;
746 bool plannedHomePositionInFile = false;
747
748 QString firstLine = stream.readLine();
749 const QStringList& version = firstLine.split(" ");
750
751 bool versionOk = false;
752 if (version.size() == 3 && version[0] == "QGC" && version[1] == "WPL") {
753 if (version[2] == "110") {
754 // ArduPilot file, planned home position is already in position 0
755 versionOk = true;
756 plannedHomePositionInFile = true;
757 } else if (version[2] == "120") {
758 // Old QGC file, no planned home position
759 versionOk = true;
760 plannedHomePositionInFile = false;
761 }
762 }
763
764 if (versionOk) {
765 MissionSettingsItem* settingsItem = _addMissionSettings(visualItems);
766
767 while (!stream.atEnd()) {
768 SimpleMissionItem* item = new SimpleMissionItem(_masterController, _flyView, true /* forLoad */);
769 if (item->load(stream)) {
770 if (firstItem && plannedHomePositionInFile) {
771 settingsItem->setCoordinate(item->coordinate());
772 } else {
773 if (TakeoffMissionItem::isTakeoffCommand(static_cast<MAV_CMD>(item->command()))) {
774 // This needs to be a TakeoffMissionItem
775 TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(item->missionItem(), _masterController, _flyView, settingsItem, false /* forLoad */);
776 item->deleteLater();
777 item = takeoffItem;
778 }
779 visualItems->append(item);
780 }
781 firstItem = false;
782 } else {
783 errorString = tr("The mission file is corrupted.");
784 return false;
785 }
786 }
787 } else {
788 errorString = tr("The mission file is not compatible with this version of %1.").arg(QCoreApplication::applicationName());
789 return false;
790 }
791
792 if (!plannedHomePositionInFile) {
793 // Update sequence numbers in DO_JUMP commands to take into account added home position in index 0
794 for (int i=1; i<visualItems->count(); i++) {
795 SimpleMissionItem* item = qobject_cast<SimpleMissionItem*>(visualItems->get(i));
796 if (item && item->command() == MAV_CMD_DO_JUMP) {
797 item->missionItem().setParam1(static_cast<int>(item->missionItem().param1()) + 1);
798 }
799 }
800 }
801
802 return true;
803}
804
805void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualItems)
806{
807 _setupNewVisualItems(loadedVisualItems);
808
809 MissionController::_scanForAdditionalSettings(_visualItems, _masterController);
810
811 _initAllVisualItems();
812
813 if (_visualItems->count() > 1) {
814 _firstItemAdded();
815 } else {
816 _allItemsRemoved();
817 }
818}
819
820bool MissionController::load(const QJsonObject& json, QString& errorString)
821{
822 QString errorStr;
823 QString errorMessage = tr("Mission: %1");
824 QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);
825
826 if (!_loadJsonMissionFileV2(json, loadedVisualItems, errorStr)) {
827 errorString = errorMessage.arg(errorStr);
828 return false;
829 }
830 _initLoadedVisualItems(loadedVisualItems);
831
832 return true;
833}
834
836{
837 QString errorStr;
838 QString errorMessage = tr("Mission: %1");
839 QByteArray bytes = file.readAll();
840 QTextStream stream(bytes);
841
843
844 QmlObjectListModel* loadedVisualItems = new QmlObjectListModel(this);
845 if (!_loadTextMissionFile(stream, loadedVisualItems, errorStr)) {
846 errorString = errorMessage.arg(errorStr);
847 return false;
848 }
849
850 _initLoadedVisualItems(loadedVisualItems);
851
852 return true;
853}
854
856{
857 for (int i=0; i<_visualItems->count(); i++) {
858 VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
860 return visualItem->readyForSaveState();
861 }
862 }
863
865}
866
867void MissionController::save(QJsonObject& json)
868{
869 json[JsonParsing::jsonVersionKey] = _missionFileVersion;
870
871 // Mission settings
872
873 MissionSettingsItem* settingsItem = _visualItems->value<MissionSettingsItem*>(0);
874 if (!settingsItem) {
875 qWarning() << "First item is not MissionSettingsItem";
876 return;
877 }
878 QJsonValue coordinateValue;
879 GeoJsonHelper::saveGeoCoordinate(settingsItem->coordinate(), true /* writeAltitude */, coordinateValue);
880 json[_jsonPlannedHomePositionKey] = coordinateValue;
881 json[_jsonFirmwareTypeKey] = _controllerVehicle->firmwareType();
882 json[_jsonVehicleTypeKey] = _controllerVehicle->vehicleType();
883 json[_jsonCruiseSpeedKey] = _controllerVehicle->defaultCruiseSpeed();
884 json[_jsonHoverSpeedKey] = _controllerVehicle->defaultHoverSpeed();
885 json[_jsonGlobalPlanAltitudeModeKey] = _globalAltFrame;
886
887 // Save the visual items
888
889 QJsonArray rgJsonMissionItems;
890 for (int i=0; i<_visualItems->count(); i++) {
891 VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
892
893 visualItem->save(rgJsonMissionItems);
894 }
895
896 // Mission settings has a special case for end mission action
897 if (settingsItem) {
898 QList<MissionItem*> rgMissionItems;
899
900 if (_convertToMissionItems(_visualItems, rgMissionItems, this /* missionItemParent */)) {
901 QJsonObject saveObject;
902 MissionItem* missionItem = rgMissionItems[rgMissionItems.count() - 1];
903 missionItem->save(saveObject);
904 rgJsonMissionItems.append(saveObject);
905 }
906 for (int i=0; i<rgMissionItems.count(); i++) {
907 rgMissionItems[i]->deleteLater();
908 }
909 }
910
911 json[_jsonItemsKey] = rgJsonMissionItems;
912}
913
914FlightPathSegment* MissionController::_createFlightPathSegmentWorker(VisualItemPair& pair, bool mavlinkTerrainFrame)
915{
916 // The takeoff goes straight up from ground to alt and then over to specified position at same alt. Which means
917 // that coord 1 altitude is the same as coord altitude.
918 bool takeoffStraightUp = pair.second->isTakeoffItem() && !_controllerVehicle->fixedWing();
919
920 QGeoCoordinate coord1 = pair.first->exitCoordinate();
921 QGeoCoordinate coord2 = pair.second->entryCoordinate();
922 double coord2AMSLAlt = pair.second->amslEntryAlt();
923 double coord1AMSLAlt = takeoffStraightUp ? coord2AMSLAlt : pair.first->amslExitAlt();
924
926 if (pair.second->isTakeoffItem()) {
928 } else if (pair.second->isLandCommand()) {
930 }
931
932 FlightPathSegment* segment = new FlightPathSegment(segmentType, coord1, coord1AMSLAlt, coord2, coord2AMSLAlt, !_flyView /* queryTerrainData */, this);
933
934 if (takeoffStraightUp) {
936 } else {
938 }
942
945
946 connect(segment, &FlightPathSegment::totalDistanceChanged, this, &MissionController::recalcTerrainProfile, Qt::QueuedConnection);
949 connect(segment, &FlightPathSegment::amslTerrainHeightsChanged, this, &MissionController::recalcTerrainProfile, Qt::QueuedConnection);
950 connect(segment, &FlightPathSegment::terrainCollisionChanged, this, &MissionController::recalcTerrainProfile, Qt::QueuedConnection);
951
952 return segment;
953}
954
955FlightPathSegment* MissionController::_addFlightPathSegment(FlightPathSegmentHashTable& prevItemPairHashTable, VisualItemPair& pair, bool mavlinkTerrainFrame)
956{
957 FlightPathSegment* segment = nullptr;
958
959 if (prevItemPairHashTable.contains(pair) && (prevItemPairHashTable[pair]->segmentType() == FlightPathSegment::SegmentTypeTerrainFrame) != mavlinkTerrainFrame) {
960 // Pair already exists and connected, just re-use
961 _flightPathSegmentHashTable[pair] = segment = prevItemPairHashTable.take(pair);
962 } else {
963 segment = _createFlightPathSegmentWorker(pair, mavlinkTerrainFrame);
964 _flightPathSegmentHashTable[pair] = segment;
965 }
966
967 _simpleFlightPathSegments.append(segment);
968
969 return segment;
970}
971
972void MissionController::_recalcFlightPathSegments(void)
973{
974 VisualItemPair lastSegmentVisualItemPair;
975 int segmentCount = 0;
976 bool firstCoordinateNotFound = true;
977 VisualMissionItem* lastFlyThroughVI = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
978 bool linkEndToHome = false;
979 bool linkStartToHome = _controllerVehicle->rover() ? true : false;
980 bool foundRTL = false;
981 bool homePositionValid = _settingsItem->coordinate().isValid();
982 bool roiActive = false;
983 bool previousItemIsIncomplete = false;
984 bool signalSplitSegmentChanged = false;
985
986 qCDebug(MissionControllerLog) << "_recalcFlightPathSegments homePositionValid" << homePositionValid;
987
988 FlightPathSegmentHashTable oldSegmentTable = _flightPathSegmentHashTable;
989
990 _missionContainsVTOLTakeoff = false;
991 _flightPathSegmentHashTable.clear();
992
993 _simpleFlightPathSegments.beginResetModel();
994 _directionArrows.beginResetModel();
995
996 _simpleFlightPathSegments.clear();
997 _directionArrows.clear();
998
999 // Mission Settings item needs to start with no segment
1000 lastFlyThroughVI->clearSimpleFlighPathSegment();
1001
1002 // 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
1003 // below since that loop won't always process all items.
1004 for (int i=1; i<_visualItems->count(); i++) {
1005 qobject_cast<VisualMissionItem*>(_visualItems->get(i))->clearSimpleFlighPathSegment();
1006 }
1007
1008 // Grovel through the list of items keeping track of things needed to correctly draw waypoints lines
1009 for (int i=1; i<_visualItems->count(); i++) {
1010 VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1011 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1012 ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1013
1014 visualItem->clearSimpleFlighPathSegment();
1015
1016 if (simpleItem) {
1017 if (roiActive) {
1018 if (_isROICancelItem(simpleItem)) {
1019 roiActive = false;
1020 }
1021 } else {
1022 if (_isROIBeginItem(simpleItem)) {
1023 roiActive = true;
1024 }
1025 }
1026
1027 MAV_CMD command = simpleItem->mavCommand();
1028 switch (command) {
1029 case MAV_CMD_NAV_TAKEOFF:
1030 case MAV_CMD_NAV_VTOL_TAKEOFF:
1031 _missionContainsVTOLTakeoff = command == MAV_CMD_NAV_VTOL_TAKEOFF;
1032 if (!linkEndToHome) {
1033 // If we still haven't found the first coordinate item and we hit a takeoff command this means the mission starts from the ground.
1034 // Link the first item back to home to show that.
1035 if (firstCoordinateNotFound) {
1036 linkStartToHome = true;
1037 }
1038 }
1039 break;
1040 case MAV_CMD_NAV_RETURN_TO_LAUNCH:
1041 linkEndToHome = true;
1042 foundRTL = true;
1043 break;
1044 default:
1045 break;
1046 }
1047 }
1048
1049 // No need to add waypoint segments after an RTL.
1050 if (foundRTL) {
1051 break;
1052 }
1053
1054 // Don't draw segments immediately after a landing item
1055 if (lastFlyThroughVI->isLandCommand()) {
1056 lastFlyThroughVI = visualItem;
1057 continue;
1058 }
1059
1060 if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
1061 // Incomplete items are complex items which are waiting for the user to complete setup before there visuals can become valid.
1062 // They may not yet have valid entry/exit coordinates associated with them while in the incomplete state.
1063 // For examples a Survey item which has no polygon set yet.
1064 if (complexItem && complexItem->isIncomplete()) {
1065 // We don't link lines from a valid item to an incomplete item
1066 previousItemIsIncomplete = true;
1067 } else if (previousItemIsIncomplete) {
1068 // We also don't link lines from an incomplete item to a valid item.
1069 previousItemIsIncomplete = false;
1070 firstCoordinateNotFound = false;
1071 lastFlyThroughVI = visualItem;
1072 } else {
1073 if (lastFlyThroughVI != _settingsItem || (homePositionValid && linkStartToHome)) {
1074 bool addDirectionArrow = false;
1075 if (i != 1) {
1076 // Direction arrows are added to the second segment and every 5 segments thereafter.
1077 // The reason for start with second segment is to prevent an arrow being added in between the home position
1078 // and a takeoff item which may be right over each other. In that case the arrow points in a random direction.
1079 if (firstCoordinateNotFound || !lastFlyThroughVI->isSimpleItem() || !visualItem->isSimpleItem()) {
1080 addDirectionArrow = true;
1081 } else if (segmentCount > 5) {
1082 segmentCount = 0;
1083 addDirectionArrow = true;
1084 }
1085 segmentCount++;
1086 }
1087
1088 lastSegmentVisualItemPair = VisualItemPair(lastFlyThroughVI, visualItem);
1089 SimpleMissionItem* lastSimpleItem = qobject_cast<SimpleMissionItem*>(lastFlyThroughVI);
1090 bool mavlinkTerrainFrame = lastSimpleItem ? lastSimpleItem->missionItem().frame() == MAV_FRAME_GLOBAL_TERRAIN_ALT : false;
1091 FlightPathSegment* segment = _addFlightPathSegment(oldSegmentTable, lastSegmentVisualItemPair, mavlinkTerrainFrame);
1092 segment->setSpecialVisual(roiActive);
1093 if (addDirectionArrow) {
1094 _directionArrows.append(segment);
1095 }
1096 if (visualItem->isCurrentItem() && _delayedSplitSegmentUpdate) {
1097 _splitSegment = segment;
1098 _delayedSplitSegmentUpdate = false;
1099 signalSplitSegmentChanged = true;
1100 }
1101 lastFlyThroughVI->setSimpleFlighPathSegment(segment);
1102 }
1103 firstCoordinateNotFound = false;
1104 lastFlyThroughVI = visualItem;
1105 }
1106 }
1107 }
1108
1109 if (linkEndToHome && lastFlyThroughVI != _settingsItem && homePositionValid) {
1110 lastSegmentVisualItemPair = VisualItemPair(lastFlyThroughVI, _settingsItem);
1111 FlightPathSegment* segment = _addFlightPathSegment(oldSegmentTable, lastSegmentVisualItemPair, false /* mavlinkTerrainFrame */);
1112 segment->setSpecialVisual(roiActive);
1113 lastFlyThroughVI->setSimpleFlighPathSegment(segment);
1114 }
1115
1116 // Add direction arrow to last segment
1117 if (lastSegmentVisualItemPair.first) {
1118 FlightPathSegment* coordVector = nullptr;
1119
1120 // 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.
1121 // check for that first and add if needed
1122
1123 if (_flightPathSegmentHashTable.contains(lastSegmentVisualItemPair)) {
1124 // Pair exists in the new table already just reuse it
1125 coordVector = _flightPathSegmentHashTable[lastSegmentVisualItemPair];
1126 } else if (oldSegmentTable.contains(lastSegmentVisualItemPair)) {
1127 // Pair already exists in old table, pull from old to new and reuse
1128 _flightPathSegmentHashTable[lastSegmentVisualItemPair] = coordVector = oldSegmentTable.take(lastSegmentVisualItemPair);
1129 } else {
1130 // Create a new segment. Since this is the fly view there is no need to wire change signals or worry about correct SegmentType
1131 coordVector = new FlightPathSegment(
1133 lastSegmentVisualItemPair.first->isSimpleItem() ? lastSegmentVisualItemPair.first->entryCoordinate() : lastSegmentVisualItemPair.first->exitCoordinate(),
1134 lastSegmentVisualItemPair.first->isSimpleItem() ? lastSegmentVisualItemPair.first->amslEntryAlt() : lastSegmentVisualItemPair.first->amslExitAlt(),
1135 lastSegmentVisualItemPair.second->entryCoordinate(),
1136 lastSegmentVisualItemPair.second->amslEntryAlt(),
1137 !_flyView /* queryTerrainData */,
1138 this);
1139 _flightPathSegmentHashTable[lastSegmentVisualItemPair] = coordVector;
1140 }
1141
1142 _directionArrows.append(coordVector);
1143 }
1144
1145 _simpleFlightPathSegments.endResetModel();
1146 _directionArrows.endResetModel();
1147
1148 // Anything left in the old table is an obsolete line object that can go
1149 qDeleteAll(oldSegmentTable);
1150
1152
1153 emit recalcTerrainProfile();
1154 if (signalSplitSegmentChanged) {
1155 emit splitSegmentChanged();
1156 }
1157}
1158
1159void MissionController::_recalcMissionFlightStatus()
1160{
1161 if (!_visualItems->count()) {
1162 return;
1163 }
1164
1165 qCDebug(MissionControllerLog) << "_recalcMissionFlightStatus";
1166
1167 _flightStatusCalc.recalc(_visualItems, _settingsItem, _controllerVehicle, _managerVehicle, _appSettings, _planViewSettings, _missionContainsVTOLTakeoff);
1168 _missionFlightStatus = _flightStatusCalc.status();
1169 _minAMSLAltitude = _flightStatusCalc.minAMSLAltitude();
1170 _maxAMSLAltitude = _flightStatusCalc.maxAMSLAltitude();
1171
1172 emit missionMaxTelemetryChanged (_missionFlightStatus.maxTelemetryDistance);
1173 emit missionTotalDistanceChanged (_missionFlightStatus.totalDistance);
1174 emit missionPlannedDistanceChanged (_missionFlightStatus.plannedDistance);
1175 emit missionHoverDistanceChanged (_missionFlightStatus.hoverDistance);
1176 emit missionCruiseDistanceChanged (_missionFlightStatus.cruiseDistance);
1177 emit missionTimeChanged ();
1180 emit batteryChangePointChanged (_missionFlightStatus.batteryChangePoint);
1181 emit batteriesRequiredChanged (_missionFlightStatus.batteriesRequired);
1182 emit minAMSLAltitudeChanged (_minAMSLAltitude);
1183 emit maxAMSLAltitudeChanged (_maxAMSLAltitude);
1184
1185 _updateTimer.start(UPDATE_TIMEOUT);
1186
1187 emit recalcTerrainProfile();
1188}
1189
1190// This will update the sequence numbers to be sequential starting from 0
1191void MissionController::_recalcSequence(void)
1192{
1193 if (_inRecalcSequence) {
1194 // Don't let this call recurse due to signalling
1195 return;
1196 }
1197
1198 // Setup ascending sequence numbers for all visual items
1199
1200 _inRecalcSequence = true;
1201 int sequenceNumber = 0;
1202 for (int i=0; i<_visualItems->count(); i++) {
1203 VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1204 item->setSequenceNumber(sequenceNumber);
1205 sequenceNumber = item->lastSequenceNumber() + 1;
1206 }
1207 _inRecalcSequence = false;
1208}
1209
1210// This will update the child item hierarchy
1211void MissionController::_recalcChildItems(void)
1212{
1213 VisualMissionItem* currentParentItem = qobject_cast<VisualMissionItem*>(_visualItems->get(0));
1214
1215 currentParentItem->childItems()->clear();
1216
1217 for (int i=1; i<_visualItems->count(); i++) {
1218 VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);
1219
1220 item->setParentItem(nullptr);
1221 item->setHasCurrentChildItem(false);
1222
1223 // Set up non-coordinate item child hierarchy
1224 if (item->specifiesCoordinate()) {
1225 item->childItems()->clear();
1226 currentParentItem = item;
1227 } else if (item->isSimpleItem()) {
1228 item->setParentItem(currentParentItem);
1229 currentParentItem->childItems()->append(item);
1230 if (item->isCurrentItem()) {
1231 currentParentItem->setHasCurrentChildItem(true);
1232 }
1233 }
1234 }
1235}
1236
1237void MissionController::_setupTreeModel(void)
1238{
1239 _visualItemsTree.beginResetModel();
1240
1241 _visualItemsTree.clear();
1242
1243 // ── Plan File group ──
1244 _planFileGroupNode.setObjectName(tr("Plan Info"));
1245 _visualItemsTree.appendItem(&_planFileGroupNode, QModelIndex(), QStringLiteral("planFileGroup"));
1246
1247 _planFileInfoMarker.setObjectName(QStringLiteral("planFileInfo"));
1248 _visualItemsTree.appendItem(&_planFileInfoMarker,
1249 _visualItemsTree.indexForObject(&_planFileGroupNode), QStringLiteral("planFileInfo"));
1250
1251 // ── Defaults group ──
1252 _defaultsGroupNode.setObjectName(tr("Defaults"));
1253 _visualItemsTree.appendItem(&_defaultsGroupNode, QModelIndex(), QStringLiteral("defaultsGroup"));
1254
1255 _defaultsInfoMarker.setObjectName(QStringLiteral("defaultsInfo"));
1256 _visualItemsTree.appendItem(&_defaultsInfoMarker,
1257 _visualItemsTree.indexForObject(&_defaultsGroupNode), QStringLiteral("defaultsInfo"));
1258
1259 // ── Mission Items group ──
1260 _missionItemsGroupNode.setObjectName(tr("Mission Items"));
1261 _visualItemsTree.appendItem(&_missionItemsGroupNode, QModelIndex(), QStringLiteral("missionGroup"));
1262
1263 // ── GeoFence group ──
1264 _fenceGroupNode.setObjectName(tr("GeoFence"));
1265 _visualItemsTree.appendItem(&_fenceGroupNode, QModelIndex(), QStringLiteral("fenceGroup"));
1266
1267 // Single marker child — delegate loads the full GeoFenceEditor
1268 _fenceEditorMarker.setObjectName(QStringLiteral("fenceEditor"));
1269 _visualItemsTree.appendItem(&_fenceEditorMarker,
1270 _visualItemsTree.indexForObject(&_fenceGroupNode), QStringLiteral("fenceEditor"));
1271
1272 // ── Rally Points group ──
1273 _rallyGroupNode.setObjectName(tr("Rally Points"));
1274 _visualItemsTree.appendItem(&_rallyGroupNode, QModelIndex(), QStringLiteral("rallyGroup"));
1275
1276 // Marker child for the rally header / instructions
1277 _rallyHeaderMarker.setObjectName(QStringLiteral("rallyHeader"));
1278 _visualItemsTree.appendItem(&_rallyHeaderMarker,
1279 _visualItemsTree.indexForObject(&_rallyGroupNode), QStringLiteral("rallyHeader"));
1280
1281 // ── Transform group ──
1282 _transformGroupNode.setObjectName(tr("Transform"));
1283 _visualItemsTree.appendItem(&_transformGroupNode, QModelIndex(), QStringLiteral("transformGroup"));
1284
1285 // Single marker child — delegate loads the inline TransformEditor
1286 _transformEditorMarker.setObjectName(QStringLiteral("transformEditor"));
1287 _visualItemsTree.appendItem(&_transformEditorMarker,
1288 _visualItemsTree.indexForObject(&_transformGroupNode), QStringLiteral("transformEditor"));
1289
1290 _visualItemsTree.endResetModel();
1291
1292 // Capture persistent indexes after the reset so they aren't invalidated
1293 _planFileGroupIndex = QPersistentModelIndex(_visualItemsTree.indexForObject(&_planFileGroupNode));
1294 _defaultsGroupIndex = QPersistentModelIndex(_visualItemsTree.indexForObject(&_defaultsGroupNode));
1295 _missionGroupIndex = QPersistentModelIndex(_visualItemsTree.indexForObject(&_missionItemsGroupNode));
1296 _fenceGroupIndex = QPersistentModelIndex(_visualItemsTree.indexForObject(&_fenceGroupNode));
1297 _rallyGroupIndex = QPersistentModelIndex(_visualItemsTree.indexForObject(&_rallyGroupNode));
1298 _transformGroupIndex = QPersistentModelIndex(_visualItemsTree.indexForObject(&_transformGroupNode));
1299}
1300
1301//-----------------------------------------------------------------------------
1302// Incremental tree model sync — Mission Items
1303//-----------------------------------------------------------------------------
1304
1305void MissionController::_syncTreeMissionItemsInserted(const QModelIndex& parent, int first, int last)
1306{
1307 Q_UNUSED(parent);
1308 for (int i = first; i <= last; i++) {
1309 auto* item = _visualItems->value<VisualMissionItem*>(i);
1310 if (item) {
1311 _visualItemsTree.insertItem(i, item, _missionGroupIndex, QStringLiteral("missionItem"));
1312 }
1313 }
1314}
1315
1316void MissionController::_syncTreeMissionItemsAboutToBeRemoved(const QModelIndex& parent, int first, int last)
1317{
1318 Q_UNUSED(parent);
1319 // Remove in reverse order so indexes stay valid
1320 for (int i = last; i >= first; i--) {
1321 _visualItemsTree.removeAt(_missionGroupIndex, i);
1322 }
1323}
1324
1325void MissionController::_syncTreeMissionItemsReset(void)
1326{
1327 // removeChildren + appendItem each fire their own row-level signals scoped
1328 // to _missionGroupIndex, so persistent indexes for other groups survive.
1329 _visualItemsTree.removeChildren(_missionGroupIndex);
1330
1331 if (_visualItems) {
1332 for (int i = 0; i < _visualItems->count(); i++) {
1333 auto* item = _visualItems->value<VisualMissionItem*>(i);
1334 if (item) {
1335 _visualItemsTree.appendItem(item, _missionGroupIndex, QStringLiteral("missionItem"));
1336 }
1337 }
1338 }
1339}
1340
1341//-----------------------------------------------------------------------------
1342// Incremental tree model sync — Rally Points
1343//-----------------------------------------------------------------------------
1344
1345void MissionController::_syncTreeRallyPointsInserted(const QModelIndex& parent, int first, int last)
1346{
1347 Q_UNUSED(parent);
1348 auto* rallyController = _masterController->rallyPointController();
1349 if (!rallyController) return;
1350
1351 // If this is the first rally point, remove the header marker
1352 if (first == 0 && _visualItemsTree.rowCount(_rallyGroupIndex) == 1) {
1353 const QModelIndex child = _visualItemsTree.index(0, 0, _rallyGroupIndex);
1354 if (_visualItemsTree.data(child, QmlObjectTreeModel::NodeTypeRole).toString() == QStringLiteral("rallyHeader")) {
1355 _visualItemsTree.removeItem(child);
1356 }
1357 }
1358
1359 auto* pts = rallyController->points();
1360 for (int i = first; i <= last; i++) {
1361 _visualItemsTree.insertItem(i, (*pts)[i], _rallyGroupIndex, QStringLiteral("rallyItem"));
1362 }
1363}
1364
1365void MissionController::_syncTreeRallyPointsAboutToBeRemoved(const QModelIndex& parent, int first, int last)
1366{
1367 Q_UNUSED(parent);
1368 for (int i = last; i >= first; i--) {
1369 _visualItemsTree.removeAt(_rallyGroupIndex, i);
1370 }
1371}
1372
1373void MissionController::_syncTreeRallyPointsRemoved(const QModelIndex& parent, int first, int last)
1374{
1375 Q_UNUSED(parent);
1376 Q_UNUSED(first);
1377 Q_UNUSED(last);
1378
1379 // Re-add the header marker once the source model has finished removing rows
1380 auto* rallyController = _masterController->rallyPointController();
1381 if (rallyController && rallyController->points()->count() == 0) {
1382 _rallyHeaderMarker.setObjectName(QStringLiteral("rallyHeader"));
1383 _visualItemsTree.appendItem(&_rallyHeaderMarker, _rallyGroupIndex, QStringLiteral("rallyHeader"));
1384 }
1385}
1386
1387void MissionController::_syncTreeRallyPointsReset(void)
1388{
1389 // removeChildren + appendItem each fire their own row-level signals scoped
1390 // to _rallyGroupIndex, so persistent indexes for other groups survive.
1391 _visualItemsTree.removeChildren(_rallyGroupIndex);
1392
1393 // Repopulate — either rally items or the header marker
1394 auto* rallyController = _masterController->rallyPointController();
1395 if (rallyController && rallyController->points()->count() > 0) {
1396 auto* pts = rallyController->points();
1397 for (int i = 0; i < pts->count(); i++) {
1398 _visualItemsTree.appendItem((*pts)[i], _rallyGroupIndex, QStringLiteral("rallyItem"));
1399 }
1400 } else {
1401 _rallyHeaderMarker.setObjectName(QStringLiteral("rallyHeader"));
1402 _visualItemsTree.appendItem(&_rallyHeaderMarker, _rallyGroupIndex, QStringLiteral("rallyHeader"));
1403 }
1404}
1405
1406void MissionController::_setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate)
1407{
1408 bool foundFirstCoordinate = false;
1409 QGeoCoordinate firstCoordinate;
1410
1411 if (_settingsItem->coordinate().isValid()) {
1412 return;
1413 }
1414
1415 // Set the planned home position to be a delta from first coordinate
1416 for (int i=1; i<_visualItems->count(); i++) {
1417 VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);
1418
1419 if (item->specifiesCoordinate() && item->entryCoordinate().isValid()) {
1420 foundFirstCoordinate = true;
1421 firstCoordinate = item->entryCoordinate();
1422 break;
1423 }
1424 }
1425
1426 // No item specifying a coordinate was found, in this case it we have a clickCoordinate use that
1427 if (!foundFirstCoordinate) {
1428 firstCoordinate = clickCoordinate;
1429 }
1430
1431 if (firstCoordinate.isValid()) {
1432 QGeoCoordinate plannedHomeCoord = firstCoordinate.atDistanceAndAzimuth(30, 0);
1433 plannedHomeCoord.setAltitude(0);
1434 _settingsItem->setCoordinate(plannedHomeCoord);
1435 }
1436}
1437
1438void MissionController::_recalcAllWithCoordinate(const QGeoCoordinate& coordinate)
1439{
1440 if (!_flyView) {
1441 _setPlannedHomePositionFromFirstCoordinate(coordinate);
1442 }
1443 _recalcSequence();
1444 _recalcChildItems();
1446 _updateTimer.start(UPDATE_TIMEOUT);
1447}
1448
1449void MissionController::_recalcAll(void)
1450{
1451 QGeoCoordinate emptyCoord;
1452 _recalcAllWithCoordinate(emptyCoord);
1453}
1454
1456void MissionController::_initAllVisualItems(void)
1457{
1458 // Setup home position at index 0
1459
1460 if (!_settingsItem) {
1461 _settingsItem = qobject_cast<MissionSettingsItem*>(_visualItems->get(0));
1462 if (!_settingsItem) {
1463 qWarning() << "First item not MissionSettingsItem";
1464 return;
1465 }
1466 }
1467
1468 connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcMissionFlightStatus);
1471
1472 for (int i=0; i<_visualItems->count(); i++) {
1473 VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1474 _initVisualItem(item);
1475
1476 TakeoffMissionItem* takeoffItem = qobject_cast<TakeoffMissionItem*>(item);
1477 if (takeoffItem) {
1478 _takeoffMissionItem = takeoffItem;
1479 }
1480 }
1481
1482 _recalcAll();
1483
1484 connect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1486
1487 // Connect for incremental tree model sync
1488 connect(_visualItems, &QAbstractItemModel::rowsInserted, this, &MissionController::_syncTreeMissionItemsInserted);
1489 connect(_visualItems, &QAbstractItemModel::rowsAboutToBeRemoved, this, &MissionController::_syncTreeMissionItemsAboutToBeRemoved);
1490 connect(_visualItems, &QAbstractItemModel::modelReset, this, &MissionController::_syncTreeMissionItemsReset);
1491
1492 // Populate tree's mission group from current _visualItems
1493 _syncTreeMissionItemsReset();
1494
1495 // Connect rally controller for incremental tree model sync
1496 auto* rallyController = _masterController->rallyPointController();
1497 if (rallyController) {
1498 auto* pts = rallyController->points();
1499 connect(pts, &QAbstractItemModel::rowsInserted, this, &MissionController::_syncTreeRallyPointsInserted);
1500 connect(pts, &QAbstractItemModel::rowsAboutToBeRemoved, this, &MissionController::_syncTreeRallyPointsAboutToBeRemoved);
1501 connect(pts, &QAbstractItemModel::rowsRemoved, this, &MissionController::_syncTreeRallyPointsRemoved);
1502 connect(pts, &QAbstractItemModel::modelReset, this, &MissionController::_syncTreeRallyPointsReset);
1503
1504 // Populate any existing rally points
1505 _syncTreeRallyPointsReset();
1506 }
1507
1508 emit visualItemsReset();
1509 emit containsItemsChanged();
1512
1513 if (!_flyView) {
1514 setCurrentPlanViewSeqNum(0, true);
1515 }
1516
1517 setDirty(false);
1518}
1519
1520void MissionController::_deinitAllVisualItems(void)
1521{
1522 disconnect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcMissionFlightStatus);
1525
1526 for (int i=0; i<_visualItems->count(); i++) {
1527 _deinitVisualItem(qobject_cast<VisualMissionItem*>(_visualItems->get(i)));
1528 }
1529
1530 disconnect(_visualItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_visualItemsDirtyChanged);
1532
1533 // Disconnect incremental tree model sync
1534 disconnect(_visualItems, &QAbstractItemModel::rowsInserted, this, &MissionController::_syncTreeMissionItemsInserted);
1535 disconnect(_visualItems, &QAbstractItemModel::rowsAboutToBeRemoved, this, &MissionController::_syncTreeMissionItemsAboutToBeRemoved);
1536 disconnect(_visualItems, &QAbstractItemModel::modelReset, this, &MissionController::_syncTreeMissionItemsReset);
1537
1538 // Disconnect rally controller tree model sync
1539 auto* rallyController = _masterController->rallyPointController();
1540 if (rallyController) {
1541 auto* pts = rallyController->points();
1542 disconnect(pts, &QAbstractItemModel::rowsInserted, this, &MissionController::_syncTreeRallyPointsInserted);
1543 disconnect(pts, &QAbstractItemModel::rowsAboutToBeRemoved, this, &MissionController::_syncTreeRallyPointsAboutToBeRemoved);
1544 disconnect(pts, &QAbstractItemModel::rowsRemoved, this, &MissionController::_syncTreeRallyPointsRemoved);
1545 disconnect(pts, &QAbstractItemModel::modelReset, this, &MissionController::_syncTreeRallyPointsReset);
1546 }
1547}
1548
1549void MissionController::_initVisualItem(VisualMissionItem* visualItem)
1550{
1551 setDirty(false);
1552
1561 connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged, this, &MissionController::_recalcSequence);
1562
1563 if (visualItem->isSimpleItem()) {
1564 // We need to track commandChanged on simple item since recalc has special handling for takeoff command
1565 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1566 if (simpleItem) {
1567 connect(&simpleItem->missionItem()._commandFact, &Fact::valueChanged, this, &MissionController::_itemCommandChanged);
1568 } else {
1569 qWarning() << "isSimpleItem == true, yet not SimpleMissionItem";
1570 }
1571 } else {
1572 ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
1573 if (complexItem) {
1578 connect(complexItem, &ComplexMissionItem::isIncompleteChanged, this, &MissionController::_recalcFlightPathSegmentsSignal, Qt::QueuedConnection);
1579 } else {
1580 qWarning() << "ComplexMissionItem not found";
1581 }
1582 }
1583}
1584
1585void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
1586{
1587 // Disconnect only signals connected to this MissionController, not all receivers.
1588 // A full wildcard disconnect(obj, 0, 0, 0) tears out internal destroyed-signal
1589 // connections that Qt (and the tree/list models) rely on for cleanup.
1590 disconnect(visualItem, nullptr, this, nullptr);
1591}
1592
1593void MissionController::_itemCommandChanged(void)
1594{
1595 _recalcChildItems();
1597}
1598
1599void MissionController::_managerVehicleChanged(Vehicle* managerVehicle)
1600{
1601 if (_managerVehicle) {
1602 _missionManager->disconnect(this);
1603 _managerVehicle->disconnect(this);
1604 _managerVehicle = nullptr;
1605 _missionManager = nullptr;
1606 }
1607
1608 _managerVehicle = managerVehicle;
1609 if (!_managerVehicle) {
1610 qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL";
1611 return;
1612 }
1613
1614 _missionManager = _managerVehicle->missionManager();
1615 connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailableFromVehicle);
1616 connect(_missionManager, &MissionManager::sendComplete, this, &MissionController::_managerSendComplete);
1617 connect(_missionManager, &MissionManager::removeAllComplete, this, &MissionController::_managerRemoveAllComplete);
1618 connect(_missionManager, &MissionManager::inProgressChanged, this, &MissionController::_inProgressChanged);
1619 connect(_missionManager, &MissionManager::progressPctChanged, this, &MissionController::_progressPctChanged);
1620 connect(_missionManager, &MissionManager::currentIndexChanged, this, &MissionController::_currentMissionIndexChanged);
1624 connect(_managerVehicle, &Vehicle::defaultCruiseSpeedChanged, this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
1625 connect(_managerVehicle, &Vehicle::defaultHoverSpeedChanged, this, &MissionController::_recalcMissionFlightStatusSignal, Qt::QueuedConnection);
1627
1630}
1631
1632void MissionController::_inProgressChanged(bool inProgress)
1633{
1634 emit syncInProgressChanged(inProgress);
1635}
1636
1637bool MissionController::_findPreviousAltitude(int newIndex, double* prevAltitude, QGroundControlQmlGlobal::AltitudeFrame* prevAltitudeMode)
1638{
1639 bool found = false;
1640 double foundAltitude = 0;
1642
1643 if (newIndex > _visualItems->count()) {
1644 return false;
1645 }
1646 newIndex--;
1647
1648 for (int i=newIndex; i>0; i--) {
1649 VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1650
1651 if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
1652 if (visualItem->isSimpleItem()) {
1653 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1654 if (simpleItem->specifiesAltitude()) {
1655 foundAltitude = simpleItem->altitude()->rawValue().toDouble();
1656 foundAltFrame = simpleItem->altitudeFrame();
1657 found = true;
1658 break;
1659 }
1660 }
1661 }
1662 }
1663
1664 if (found) {
1665 *prevAltitude = foundAltitude;
1666 *prevAltitudeMode = foundAltFrame;
1667 }
1668
1669 return found;
1670}
1671
1672double MissionController::_normalizeLat(double lat)
1673{
1674 // Normalize latitude to range: 0 to 180, S to N
1675 return lat + 90.0;
1676}
1677
1678double MissionController::_normalizeLon(double lon)
1679{
1680 // Normalize longitude to range: 0 to 360, W to E
1681 return lon + 180.0;
1682}
1683
1685MissionSettingsItem* MissionController::_addMissionSettings(QmlObjectListModel* visualItems)
1686{
1687 qCDebug(MissionControllerLog) << "_addMissionSettings";
1688
1690 visualItems->insert(0, settingsItem);
1691
1692 if (visualItems == _visualItems) {
1693 _settingsItem = settingsItem;
1694 }
1695
1696 return settingsItem;
1697}
1698
1700{
1701
1702 int resumeIndex = 0;
1703
1704 if (_flyView) {
1705 resumeIndex = _missionManager->lastCurrentIndex() + (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() ? 0 : 1);
1706 if (resumeIndex > 1 && resumeIndex != _visualItems->value<VisualMissionItem*>(_visualItems->count() - 1)->sequenceNumber()) {
1707 // Resume at the item previous to the item we were heading towards
1708 resumeIndex--;
1709 } else {
1710 resumeIndex = 0;
1711 }
1712 }
1713
1714 return resumeIndex;
1715}
1716
1718{
1719 if (!_flyView) {
1720 return -1;
1721 } else {
1722 int currentIndex = _missionManager->currentIndex();
1723 if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1724 currentIndex++;
1725 }
1726 return currentIndex;
1727 }
1728}
1729
1730void MissionController::_currentMissionIndexChanged(int sequenceNumber)
1731{
1732 if (_flyView) {
1733 if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1734 sequenceNumber++;
1735 }
1736
1737 for (int i=0; i<_visualItems->count(); i++) {
1738 VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
1739 item->setIsCurrentItem(item->sequenceNumber() == sequenceNumber);
1740 }
1742 }
1743}
1744
1746{
1747 return _missionManager->inProgress();
1748}
1749
1751{
1752 return _visualItems ? _visualItems->dirty() : false;
1753}
1754
1755
1757{
1758 if (_visualItems) {
1759 _visualItems->setDirty(dirty);
1760 }
1761}
1762
1763void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualItems, PlanMasterController* masterController)
1764{
1765 // First we look for Landing Patterns which are at the end
1768 }
1769
1770 int scanIndex = 0;
1771 while (scanIndex < visualItems->count()) {
1772 VisualMissionItem* visualItem = visualItems->value<VisualMissionItem*>(scanIndex);
1773
1774 qCDebug(MissionControllerLog) << "MissionController::_scanForAdditionalSettings count:scanIndex" << visualItems->count() << scanIndex;
1775
1776 if (!_flyView) {
1777 MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
1778 if (settingsItem) {
1779 scanIndex++;
1780 settingsItem->scanForMissionSettings(visualItems, scanIndex);
1781 continue;
1782 }
1783 }
1784
1785 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
1786 if (simpleItem) {
1787 scanIndex++;
1788 simpleItem->scanForSections(visualItems, scanIndex, masterController);
1789 } else {
1790 // Complex item, can't have sections
1791 scanIndex++;
1792 }
1793 }
1794}
1795
1797{
1798 return _visualItems ? _visualItems->count() > 1 : false;
1799}
1800
1802{
1803 if (_masterController->offline()) {
1804 qCCritical(MissionControllerLog) << "MissionControllerLog::removeAllFromVehicle called while offline";
1805 } else if (syncInProgress()) {
1806 qCCritical(MissionControllerLog) << "MissionControllerLog::removeAllFromVehicle called while syncInProgress";
1807 } else {
1808 _itemsRequested = true;
1809 _missionManager->removeAll();
1810 }
1811}
1812
1814{
1815 return QGCCorePlugin::instance()->complexMissionItemNames(_controllerVehicle);
1816}
1817
1819{
1820 if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle()) {
1821 resumeIndex--;
1822 }
1823 _missionManager->generateResumeMission(resumeIndex);
1824}
1825
1827{
1828 if (_settingsItem) {
1829 return _settingsItem->coordinate();
1830 } else {
1831 return QGeoCoordinate();
1832 }
1833}
1834
1836{
1837 return _settingsItem && _settingsItem->coordinate().isValid();
1838}
1839
1840void MissionController::setHomePosition(QGeoCoordinate coordinate)
1841{
1842 if (_settingsItem) {
1843 _settingsItem->setCoordinate(coordinate);
1844 }
1845}
1846
1848{
1849 double defaultAltitude = _appSettings->defaultMissionItemAltitude()->rawValue().toDouble();
1850
1851 for (int i=1; i<_visualItems->count(); i++) {
1852 VisualMissionItem* item = _visualItems->value<VisualMissionItem*>(i);
1853 item->applyNewAltitude(defaultAltitude);
1854 }
1855}
1856
1857void MissionController::_progressPctChanged(double progressPct)
1858{
1859 if (!QGC::fuzzyCompare(progressPct, _progressPct)) {
1860 _progressPct = progressPct;
1862 }
1863}
1864
1865void MissionController::_visualItemsDirtyChanged(bool dirty)
1866{
1867 // We could connect signal to signal and not need this but this is handy for setting a breakpoint on
1868 emit dirtyChanged(dirty);
1869}
1870
1872{
1873 qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle _flyView" << _flyView;
1874 if (_masterController->offline()) {
1875 qCCritical(MissionControllerLog) << "MissionController::showPlanFromManagerVehicle called while offline";
1876 return true; // stops further propagation of showPlanFromManagerVehicle due to error
1877 } else {
1878 if (!_managerVehicle->initialPlanRequestComplete()) {
1879 // The vehicle hasn't completed initial load, we can just wait for newMissionItemsAvailable to be signalled automatically
1880 qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle: !initialPlanRequestComplete, wait for signal";
1881 return true;
1882 } else if (syncInProgress()) {
1883 // If the sync is already in progress, newMissionItemsAvailable will be signalled automatically when it is done. So no need to do anything.
1884 qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle: syncInProgress wait for signal";
1885 return true;
1886 } else {
1887 // Sync has already completed, fake a _newMissionItemsAvailable with the current items
1888 qCDebug(MissionControllerLog) << "showPlanFromManagerVehicle: sync complete simulate signal";
1889 _itemsRequested = true;
1890 _newMissionItemsAvailableFromVehicle(false /* removeAllRequested */);
1891 return false;
1892 }
1893 }
1894}
1895
1896void MissionController::_managerSendComplete(bool error)
1897{
1898 // Fly view always reloads on send complete
1899 if (!error && _flyView) {
1901 }
1902}
1903
1904void MissionController::_managerRemoveAllComplete(bool error)
1905{
1906 if (!error) {
1907 // Remove all from vehicle so we always update
1909 }
1910}
1911
1912bool MissionController::_isROIBeginItem(SimpleMissionItem* simpleItem)
1913{
1914 return simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI_LOCATION ||
1915 simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET ||
1916 (simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI &&
1917 static_cast<int>(simpleItem->missionItem().param1()) == MAV_ROI_LOCATION);
1918}
1919
1920bool MissionController::_isROICancelItem(SimpleMissionItem* simpleItem)
1921{
1922 return simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI_NONE ||
1923 (simpleItem->mavCommand() == MAV_CMD_DO_SET_ROI &&
1924 static_cast<int>(simpleItem->missionItem().param1()) == MAV_ROI_NONE);
1925}
1926
1927void MissionController::setCurrentPlanViewSeqNum(int sequenceNumber, bool force)
1928{
1929 if (_visualItems && (force || sequenceNumber != _currentPlanViewSeqNum)) {
1930 qCDebug(MissionControllerLog) << "setCurrentPlanViewSeqNum";
1931 bool foundLand = false;
1932 int takeoffSeqNum = -1;
1933 int landSeqNum = -1;
1934 int lastFlyThroughSeqNum = -1;
1935
1936 _splitSegment = nullptr;
1937 _currentPlanViewItem = nullptr;
1938 _currentPlanViewSeqNum = -1;
1939 _currentPlanViewVIIndex = -1;
1940 _onlyInsertTakeoffValid = false;
1941 _isInsertTakeoffValid = true;
1942 _isInsertLandValid = true;
1943 _isROIActive = false;
1944 _isROIBeginCurrentItem = false;
1945 _flyThroughCommandsAllowed = true;
1946 _previousCoordinate = QGeoCoordinate();
1947
1948 bool noItemsAddedYet = _visualItems->count() == 1;
1949 if (_masterController->controllerVehicle()->supports()->takeoffMissionCommand() && !_planViewSettings->takeoffItemNotRequired()->rawValue().toBool() && noItemsAddedYet) {
1950 _onlyInsertTakeoffValid = true;
1951 }
1952
1953 for (int viIndex=0; viIndex<_visualItems->count(); viIndex++) {
1954 VisualMissionItem* pVI = qobject_cast<VisualMissionItem*>(_visualItems->get(viIndex));
1955 SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(pVI);
1956 int currentSeqNumber = pVI->sequenceNumber();
1957
1958 if (sequenceNumber != 0 && currentSeqNumber <= sequenceNumber) {
1959 if (pVI->specifiesCoordinate() && !pVI->isStandaloneCoordinate()) {
1960 // Coordinate based flight commands prior to where the takeoff would be inserted
1961 _isInsertTakeoffValid = false;
1962 }
1963 }
1964
1965 if (qobject_cast<TakeoffMissionItem*>(pVI)) {
1966 takeoffSeqNum = currentSeqNumber;
1967 _isInsertTakeoffValid = false;
1968 }
1969
1970 if (!foundLand) {
1971 if (simpleItem) {
1972 switch (simpleItem->mavCommand()) {
1973 case MAV_CMD_NAV_LAND:
1974 case MAV_CMD_NAV_VTOL_LAND:
1975 case MAV_CMD_DO_LAND_START:
1976 case MAV_CMD_NAV_RETURN_TO_LAUNCH:
1977 foundLand = true;
1978 landSeqNum = currentSeqNumber;
1979 break;
1980 default:
1981 break;
1982 }
1983 } else {
1984 FixedWingLandingComplexItem* fwLanding = qobject_cast<FixedWingLandingComplexItem*>(pVI);
1985 if (fwLanding) {
1986 foundLand = true;
1987 landSeqNum = currentSeqNumber;
1988 }
1989 }
1990 }
1991
1992 if (simpleItem) {
1993 // Remember previous coordinate
1994 if (currentSeqNumber < sequenceNumber && simpleItem->specifiesCoordinate() && !simpleItem->isStandaloneCoordinate()) {
1995 _previousCoordinate = simpleItem->coordinate();
1996 }
1997
1998 // ROI state handling
1999 if (currentSeqNumber <= sequenceNumber) {
2000 if (_isROIActive) {
2001 if (_isROICancelItem(simpleItem)) {
2002 _isROIActive = false;
2003 }
2004 } else {
2005 if (_isROIBeginItem(simpleItem)) {
2006 _isROIActive = true;
2007 }
2008 }
2009 }
2010 if (currentSeqNumber == sequenceNumber && _isROIBeginItem(simpleItem)) {
2011 _isROIBeginCurrentItem = true;
2012 }
2013 }
2014
2015 if (viIndex != 0) {
2016 // Complex items are assumed to be fly through
2017 if (!simpleItem || (simpleItem->specifiesCoordinate() && !simpleItem->isStandaloneCoordinate())) {
2018 lastFlyThroughSeqNum = currentSeqNumber;
2019 }
2020 }
2021
2022 if (currentSeqNumber == sequenceNumber) {
2023 pVI->setIsCurrentItem(true);
2024 pVI->setHasCurrentChildItem(false);
2025
2026 _currentPlanViewItem = pVI;
2027 _currentPlanViewSeqNum = sequenceNumber;
2028 _currentPlanViewVIIndex = viIndex;
2029
2030 if (pVI->specifiesCoordinate()) {
2031 if (!pVI->isStandaloneCoordinate()) {
2032 // Determine split segment used to display line split editing ui.
2033 for (int j=viIndex-1; j>0; j--) {
2034 VisualMissionItem* pPrev = qobject_cast<VisualMissionItem*>(_visualItems->get(j));
2035 if (pPrev->specifiesCoordinate() && !pPrev->isStandaloneCoordinate()) {
2036 VisualItemPair splitPair(pPrev, pVI);
2037 if (_flightPathSegmentHashTable.contains(splitPair)) {
2038 _splitSegment = _flightPathSegmentHashTable[splitPair];
2039 } else {
2040 // The recalc of flight path segments hasn't happened yet since it is delayed and compressed.
2041 // So we need to register the fact that we need a split segment update and it will happen in the recalc instead.
2042 _delayedSplitSegmentUpdate = true;
2043 }
2044 break;
2045 }
2046 }
2047 }
2048 } else if (pVI->parentItem()) {
2049 pVI->parentItem()->setHasCurrentChildItem(true);
2050 }
2051 } else {
2052 pVI->setIsCurrentItem(false);
2053 // Child items will always be later in the mission sequence, so this should be correct, to be sure the HasCurrentChildItem is cleared
2054 pVI->setHasCurrentChildItem(false);
2055 }
2056 }
2057
2058 if (takeoffSeqNum != -1) {
2059 // Takeoff item was found which means mission starts from ground
2060 if (sequenceNumber < takeoffSeqNum) {
2061 // Land is only valid after the takeoff item.
2062 _isInsertLandValid = false;
2063 // Fly through commands are not allowed prior to the takeoff command
2064 _flyThroughCommandsAllowed = false;
2065 }
2066 }
2067
2068 if (lastFlyThroughSeqNum != -1) {
2069 // Land item must be after any fly through coordinates
2070 if (sequenceNumber < lastFlyThroughSeqNum) {
2071 _isInsertLandValid = false;
2072 }
2073 }
2074
2075 if (foundLand && !multipleLandPatternsAllowed()) {
2076 _isInsertLandValid = false;
2077 if (sequenceNumber >= landSeqNum) {
2078 // Can't have fly through commands after a land item
2079 _flyThroughCommandsAllowed = false;
2080 }
2081 }
2082
2083 if (_hasLandItem != foundLand) {
2084 // Update hasLandItem if the presence of a landing item has changed
2085 _hasLandItem = foundLand;
2086 emit hasLandItemChanged();
2087 }
2088
2089 // These are not valid when only takeoff is allowed
2090 _isInsertLandValid = _isInsertLandValid && !_onlyInsertTakeoffValid;
2091 _flyThroughCommandsAllowed = _flyThroughCommandsAllowed && !_onlyInsertTakeoffValid;
2092
2093 // These 10 properties are all recomputed together above, so a single signal is sufficient.
2094 // QML property bindings list planViewStateChanged as their NOTIFY signal which means
2095 // one emit re-evaluates all dependent bindings in one pass instead of 10 separate updates.
2096 // splitSegmentChanged is kept separate because PlanView.qml has an explicit onSplitSegmentChanged handler.
2097 emit planViewStateChanged();
2098 emit splitSegmentChanged();
2099 }
2100}
2101
2102void MissionController::repositionMission(const QGeoCoordinate& newHome,
2103 bool repositionTakeoffItems,
2104 bool repositionLandingItems)
2105{
2106 if (!newHome.isValid()) {
2107 qCWarning(MissionControllerLog) << "Cannot reposition mission to an invalid coordinate";
2108 return;
2109 }
2110
2111 if (!_settingsItem || !_settingsItem->coordinate().isValid()) {
2112 qCWarning(MissionControllerLog) << "Cannot reposition mission while home is invalid";
2113 return;
2114 }
2115
2116 const QGeoCoordinate oldHome = _settingsItem->coordinate();
2117
2118 for (int i = 0; i < _visualItems->count(); ++i) {
2119 auto* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
2120 if (!item || !item->specifiesCoordinate() || item->isStandaloneCoordinate()) {
2121 continue;
2122 }
2123
2124 if ((!repositionTakeoffItems && item->isTakeoffItem()) ||
2125 (!repositionLandingItems && item->isLandCommand())) {
2126 continue;
2127 }
2128
2129 const QGeoCoordinate oldCoord = item->coordinate();
2130 if (!oldCoord.isValid()) {
2131 continue;
2132 }
2133
2134 const double distanceMeters = oldHome.distanceTo(oldCoord);
2135 const double azimuthDegrees = oldHome.azimuthTo(oldCoord);
2136
2137 QGeoCoordinate newCoord = newHome.atDistanceAndAzimuth(distanceMeters, azimuthDegrees);
2138 item->setCoordinate(newCoord);
2139 }
2140
2141 setDirty(true);
2142}
2143
2145 double northMeters,
2146 double upMeters,
2147 bool offsetTakeoffItems,
2148 bool offsetLandingItems)
2149{
2150 if (!qFuzzyIsNull(eastMeters) || !qFuzzyIsNull(northMeters)) {
2151 const double distanceMeters = qSqrt(eastMeters * eastMeters + northMeters * northMeters);
2152 double azimuthDegrees = 0.0;
2153 if (!qFuzzyIsNull(distanceMeters)) {
2154 const double azimuthRadians = qAtan2(eastMeters, northMeters);
2155 azimuthDegrees = qRadiansToDegrees(azimuthRadians);
2156 }
2157
2158 for (int i = 0; i < _visualItems->count(); ++i) {
2159 auto* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
2160 if (!item || !item->specifiesCoordinate() || item->isStandaloneCoordinate()) {
2161 continue;
2162 }
2163
2164 if ((!offsetTakeoffItems && item->isTakeoffItem()) ||
2165 (!offsetLandingItems && item->isLandCommand())) {
2166 continue;
2167 }
2168
2169 const QGeoCoordinate oldCoord = item->coordinate();
2170 if (!oldCoord.isValid()) {
2171 continue;
2172 }
2173
2174 item->setCoordinate(oldCoord.atDistanceAndAzimuth(distanceMeters, azimuthDegrees));
2175 }
2176
2177 setDirty(true);
2178 }
2179
2180 if (!qFuzzyIsNull(upMeters)) {
2181 for (int i = 0; i < _visualItems->count(); ++i) {
2182 auto* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
2183 if (!item || item == _settingsItem) {
2184 continue;
2185 }
2186
2187 if ((!offsetTakeoffItems && item->isTakeoffItem()) ||
2188 (!offsetLandingItems && item->isLandCommand())) {
2189 continue;
2190 }
2191
2192 if (!item->specifiesCoordinate() && !item->specifiesAltitudeOnly()) {
2193 continue;
2194 }
2195
2196 if (!qIsNaN(item->editableAlt())) {
2197 item->applyNewAltitude(item->editableAlt() + upMeters);
2198 }
2199 }
2200
2201 setDirty(true);
2202 }
2203}
2204
2206 bool rotateTakeoffItems,
2207 bool rotateLandingItems)
2208{
2209 if (qFuzzyIsNull(degreesCW)) {
2210 return;
2211 }
2212
2213 if (!_settingsItem || !_settingsItem->coordinate().isValid()) {
2214 qCWarning(MissionControllerLog) << "Cannot rotate mission while home is invalid";
2215 return;
2216 }
2217
2218 const QGeoCoordinate home = _settingsItem->coordinate();
2219
2220 for (int i = 0; i < _visualItems->count(); ++i) {
2221 auto* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
2222 if (!item || !item->specifiesCoordinate() || item->isStandaloneCoordinate()) {
2223 continue;
2224 }
2225
2226 if ((!rotateTakeoffItems && item->isTakeoffItem()) ||
2227 (!rotateLandingItems && item->isLandCommand())) {
2228 continue;
2229 }
2230
2231 const QGeoCoordinate oldCoord = item->coordinate();
2232 if (!oldCoord.isValid()) {
2233 continue;
2234 }
2235
2236 const double distanceMeters = home.distanceTo(oldCoord);
2237 if (qFuzzyIsNull(distanceMeters)) {
2238 continue;
2239 }
2240 const double azimuthDegrees = home.azimuthTo(oldCoord);
2241
2242 QGeoCoordinate newCoord = home.atDistanceAndAzimuth(distanceMeters, azimuthDegrees + degreesCW);
2243 item->setCoordinate(newCoord);
2244 }
2245
2246 setDirty(true);
2247}
2248
2249void MissionController::_updateTimeout()
2250{
2251 QGeoCoordinate firstCoordinate;
2252 QGeoCoordinate takeoffCoordinate;
2253 QGCGeoBoundingCube boundingCube;
2254 double north = 0.0;
2255 double south = 180.0;
2256 double east = 0.0;
2257 double west = 360.0;
2258 double minAlt = QGCGeoBoundingCube::MaxAlt;
2259 double maxAlt = QGCGeoBoundingCube::MinAlt;
2260 for (int i = 1; i < _visualItems->count(); i++) {
2261 VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
2262 if(item->isSimpleItem()) {
2263 SimpleMissionItem* pSimpleItem = qobject_cast<SimpleMissionItem*>(item);
2264 if(pSimpleItem) {
2265 switch(pSimpleItem->command()) {
2266 case MAV_CMD_NAV_TAKEOFF:
2267 case MAV_CMD_NAV_WAYPOINT:
2268 case MAV_CMD_NAV_LAND:
2269 if(pSimpleItem->coordinate().isValid()) {
2270 double alt = 0.0;
2271 if (!pSimpleItem->altitude()->rawValue().isNull() && !qIsNaN(pSimpleItem->altitude()->rawValue().toDouble())) {
2272 alt = pSimpleItem->altitude()->rawValue().toDouble();
2273 }
2274 if((MAV_CMD)pSimpleItem->command() == MAV_CMD_NAV_TAKEOFF) {
2275 takeoffCoordinate = pSimpleItem->coordinate();
2276 takeoffCoordinate.setAltitude(alt);
2277 minAlt = maxAlt = alt;
2278 } else if(!firstCoordinate.isValid()) {
2279 firstCoordinate = pSimpleItem->coordinate();
2280 }
2281 double lat = pSimpleItem->coordinate().latitude() + 90.0;
2282 double lon = pSimpleItem->coordinate().longitude() + 180.0;
2283 north = fmax(north, lat);
2284 south = fmin(south, lat);
2285 east = fmax(east, lon);
2286 west = fmin(west, lon);
2287 minAlt = fmin(minAlt, alt);
2288 maxAlt = fmax(maxAlt, alt);
2289 }
2290 break;
2291 default:
2292 break;
2293 }
2294 }
2295 } else {
2296 ComplexMissionItem* pComplexItem = qobject_cast<ComplexMissionItem*>(item);
2297 if(pComplexItem) {
2298 QGCGeoBoundingCube bc = pComplexItem->boundingCube();
2299 if(bc.isValid()) {
2300 if(!firstCoordinate.isValid() && pComplexItem->entryCoordinate().isValid()) {
2301 firstCoordinate = pComplexItem->entryCoordinate();
2302 }
2303 north = fmax(north, bc.pointNW.latitude() + 90.0);
2304 south = fmin(south, bc.pointSE.latitude() + 90.0);
2305 east = fmax(east, bc.pointNW.longitude() + 180.0);
2306 west = fmin(west, bc.pointSE.longitude() + 180.0);
2307 minAlt = fmin(minAlt, bc.pointNW.altitude());
2308 maxAlt = fmax(maxAlt, bc.pointSE.altitude());
2309 }
2310 }
2311 }
2312 }
2313 //-- Figure out where this thing is taking off from
2314 if(!takeoffCoordinate.isValid()) {
2315 if(firstCoordinate.isValid()) {
2316 takeoffCoordinate = firstCoordinate;
2317 } else {
2319 }
2320 }
2321 //-- Build bounding "cube"
2322 boundingCube = QGCGeoBoundingCube(
2323 QGeoCoordinate(north - 90.0, west - 180.0, minAlt),
2324 QGeoCoordinate(south - 90.0, east - 180.0, maxAlt));
2325 if(_travelBoundingCube != boundingCube || _takeoffCoordinate != takeoffCoordinate) {
2326 _takeoffCoordinate = takeoffCoordinate;
2327 _travelBoundingCube = boundingCube;
2329 qCDebug(MissionControllerLog) << "Bounding cube:" << _travelBoundingCube.pointNW << _travelBoundingCube.pointSE;
2330 }
2331}
2332
2333void MissionController::_complexBoundingBoxChanged()
2334{
2335 _updateTimer.start(UPDATE_TIMEOUT);
2336}
2337
2339 const int count = _visualItems->count();
2340
2341 for (int i = 0; i < count; i++) {
2342 QObject *obj = _visualItems->get(i);
2343
2344 LandingComplexItem *landingItem = qobject_cast<LandingComplexItem *>(obj);
2345 if (landingItem) {
2346 return landingItem == item;
2347 }
2348 }
2349
2350 return false;
2351}
2352
2354{
2355 return _visualItems->count() <= 1;
2356}
2357
2358void MissionController::_forceRecalcOfAllowedBits(void)
2359{
2360 // Force a recalc of allowed bits
2361 setCurrentPlanViewSeqNum(_currentPlanViewSeqNum, true /* force */);
2362}
2363
2364void MissionController::_allItemsRemoved(void)
2365{
2366 // When there are no mission items we track changes to firmware/vehicle type. This allows a vehicle connection
2367 // to adjust these items.
2368 _controllerVehicle->trackFirmwareVehicleTypeChanges();
2369}
2370
2371void MissionController::_firstItemAdded(void)
2372{
2373 // As soon as the first item is added we lock the firmware/vehicle type to current values. So if you then connect a vehicle
2374 // it will not affect these values.
2375 _controllerVehicle->stopTrackingFirmwareVehicleTypeChanges();
2376}
2377
2379{
2380 if (_managerVehicle->isOfflineEditingVehicle()) {
2382 }
2383 if (_managerVehicle->armed() && _managerVehicle->flightMode() == _managerVehicle->missionFlightMode()) {
2385 }
2386 if (_controllerVehicle->firmwareType() != _managerVehicle->firmwareType() || QGCMAVLink::vehicleClass(_controllerVehicle->vehicleType()) != QGCMAVLink::vehicleClass(_managerVehicle->vehicleType())) {
2388 }
2390}
2391
2396
2405
2407{
2408 if (_globalAltFrame != altFrame) {
2409 _globalAltFrame = altFrame;
2411 }
2412}
#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:10
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)
bool specifyGimbal(void) const
void isIncompleteChanged(void)
void boundingCubeChanged(void)
static constexpr const char * jsonComplexItemTypeKey
This mission item attribute specifies the type of the complex item.
void greatestDistanceToChanged(void)
bool isIncomplete(void) const
virtual void applyPreviousAltitudeFrame(QGroundControlQmlGlobal::AltitudeFrame prevAltFrame, double prevAltitude)
void maxAMSLAltitudeChanged(void)
virtual bool load(const QJsonObject &complexObject, int sequenceNumber, QString &errorString)=0
void minAMSLAltitudeChanged(void)
void complexDistanceChanged(void)
void rawValueChanged(const QVariant &value)
void setRawValue(const QVariant &value)
Definition Fact.cc:128
QVariant rawValue() const
Value after translation.
Definition Fact.h:85
void valueChanged(const QVariant &value)
This signal is only meant for use by the QT property system. It should not be connected to by client ...
virtual QList< MAV_CMD > supportedMissionCommands(QGCMAVLinkTypes::VehicleClass_t) const
List of supported mission commands. Empty list for all commands supported.
virtual bool sendHomePositionToVehicle() const
virtual bool hasGimbal(Vehicle *vehicle, bool &rollSupported, bool &pitchSupported, bool &yawSupported) const
static bool scanForItems(QmlObjectListModel *visualItems, bool flyView, PlanMasterController *masterController)
Scans the loaded items for a landing pattern complex item.
static constexpr const char * canonicalName
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)
static MissionCommandTree * instance()
void minAMSLAltitudeChanged(double minAMSLAltitude)
Q_INVOKABLE void resumeMission(int resumeIndex)
double progressPct(void) const
Q_INVOKABLE int visualItemIndexForObject(QObject *object) const
Returns the visual item index for the given VisualMissionItem object, or -1 if not found.
void complexMissionItemsChanged(void)
Q_INVOKABLE void setHomePosition(QGeoCoordinate coordinate)
Set the planned home position from a map click.
bool showPlanFromManagerVehicle(void) final
Q_INVOKABLE SendToVehiclePreCheckState sendToVehiclePreCheck(void)
bool dirty(void) const final
Q_INVOKABLE VisualMissionItem * insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int visualItemIndex, bool makeCurrentItem=false)
void batteriesRequiredChanged(int batteriesRequired)
bool loadTextFile(QFile &file, QString &errorString)
void multipleLandPatternsAllowedChanged(void)
bool multipleLandPatternsAllowed(void) const
Q_INVOKABLE VisualMissionItem * insertTakeoffItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
QGeoCoordinate takeoffCoordinate()
Q_INVOKABLE VisualMissionItem * insertLandItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
Q_INVOKABLE void offsetMission(double eastMeters, double northMeters, double upMeters=0.0, bool offsetTakeoffItems=false, bool offsetLandingItems=false)
Q_INVOKABLE void setCurrentPlanViewSeqNum(int sequenceNumber, bool force)
void maxAMSLAltitudeChanged(double maxAMSLAltitude)
void removeAllFromVehicle(void) final
void homePositionSetChanged(void)
void recalcTerrainProfile(void)
void missionPlannedDistanceChanged(double missionPlannedDistance)
void missionTotalDistanceChanged(double missionTotalDistance)
void hasLandItemChanged(void)
void _recalcFlightPathSegmentsSignal(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 splitSegmentChanged(void)
Q_INVOKABLE void repositionMission(const QGeoCoordinate &newHome, bool repositionTakeoffItems=true, bool repositionLandingItems=true)
void resumeMissionReady(void)
@ SendToVehiclePreCheckStateFirwmareVehicleMismatch
void batteryChangePointChanged(int batteryChangePoint)
Q_INVOKABLE void rotateMission(double degreesCW, bool rotateTakeoffItems=false, bool rotateLandingItems=false)
void addMissionToKML(KMLPlanDomDocument &planKML)
void _recalcMissionFlightStatusSignal(void)
void missionHoverDistanceChanged(double missionHoverDistance)
bool syncInProgress(void) const final
void sendToVehicle(void) final
void resumeMissionIndexChanged(void)
void currentMissionIndexChanged(int currentMissionIndex)
Q_INVOKABLE VisualMissionItem * insertROIMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
void plannedHomePositionChanged(QGeoCoordinate plannedHomePosition)
Q_INVOKABLE void removeVisualItem(int viIndex)
bool isEmpty(void) const
void newItemsFromVehicle(void)
void setGlobalAltitudeFrame(QGroundControlQmlGlobal::AltitudeFrame altFrame)
void save(QJsonObject &json) final
Q_INVOKABLE VisualMissionItem * insertSimpleMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
void missionHoverTimeChanged(void)
bool isFirstLandingComplexItem(const LandingComplexItem *item) const
QGeoCoordinate plannedHomePosition(void) const
bool homePositionSet(void) const
bool containsItems(void) const final
void progressPctChanged(double progressPct)
void missionCruiseTimeChanged(void)
QGroundControlQmlGlobal::AltitudeFrame globalAltitudeFrame(void)
int readyForSaveState(void) const
QGroundControlQmlGlobal::AltitudeFrame globalAltitudeFrameDefault(void)
void removeAll(void) final
Removes all from controller only.
void visualItemsReset(void)
void missionBoundingCubeChanged(void)
QVariantList complexMissionItems(void) const
void missionTimeChanged(void)
Q_INVOKABLE 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 planViewStateChanged(void)
All plan-view properties are recomputed together in setCurrentPlanViewSeqNum, so one signal covers th...
void globalAltitudeFrameChanged(void)
void missionCruiseDistanceChanged(double missionCruiseDistance)
void resumeMissionUploadFail(void)
void loadFromVehicle(void) final
Q_INVOKABLE VisualMissionItem * insertCancelROIMissionItem(int visualItemIndex, bool makeCurrentItem=false)
int resumeMissionIndex(void) const
Q_INVOKABLE VisualMissionItem * insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int visualItemIndex, bool makeCurrentItem=false)
QmlObjectListModel * visualItems(void)
void reset(Vehicle *controllerVehicle, Vehicle *managerVehicle, bool missionContainsVTOLTakeoff)
Resets the flight status fields to defaults based on vehicle properties.
const MissionFlightStatus_t & status() const
void recalc(QmlObjectListModel *visualItems, MissionSettingsItem *settingsItem, Vehicle *controllerVehicle, Vehicle *managerVehicle, AppSettings *appSettings, PlanViewSettings *planViewSettings, bool missionContainsVTOLTakeoff)
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.
bool scanForMissionSettings(QmlObjectListModel *visualItems, int scanIndex)
Scans the loaded items for settings items.
QGeoCoordinate coordinate(void) const final
void setCoordinate(const QGeoCoordinate &coordinate) final
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)
void countChanged(int count)
This is the abstract base clas for Plan Element controllers.
void syncInProgressChanged(bool syncInProgress)
PlanMasterController * masterController(void)
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:22
Master controller for mission, fence, rally.
Vehicle * controllerVehicle(void)
void managerVehicleChanged(Vehicle *managerVehicle)
RallyPointController * rallyPointController(void)
virtual ComplexMissionItem * createComplexMissionItem(const QString &complexItemType, PlanMasterController *masterController, bool flyView, const QString &kmlOrShpFile=QString())
virtual QVariantList complexMissionItemNames(Vehicle *vehicle)
static QGCCorePlugin * instance()
Q_INVOKABLE bool isValid() const
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
T value(int index) const
void setDirty(bool dirty) override final
Q_INVOKABLE 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.
Q_INVOKABLE QObject * removeItem(const QModelIndex &index)
QObject * removeAt(const QModelIndex &parentIndex, int row)
QModelIndex index(int row, int column, const QModelIndex &parent=QModelIndex()) const override
Q_INVOKABLE QModelIndex indexForObject(QObject *object) const
Searches the entire tree for object and returns its QModelIndex (invalid if not found)
Q_INVOKABLE QModelIndex insertItem(int row, QObject *object, const QModelIndex &parentIndex=QModelIndex())
Inserts object at row under parentIndex. Returns the new item's index.
Q_INVOKABLE 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.
static SettingsManager * instance()
AppSettings * appSettings() const
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
bool scanForSections(QmlObjectListModel *visualItems, int scanIndex, PlanMasterController *masterController)
int lastSequenceNumber(void) const final
MAV_CMD mavCommand(void) const
bool specifiesAltitude(void) const
QGeoCoordinate coordinate(void) const final
virtual bool load(QTextStream &loadStream)
void setCoordinate(const QGeoCoordinate &coordinate) override
void setCommand(int command)
int command(void) const
void setAltitudeFrame(QGroundControlQmlGlobal::AltitudeFrame altitudeFrame)
MissionItem & missionItem(void)
QGroundControlQmlGlobal::AltitudeFrame altitudeFrame(void) const
Takeoff mission item is a special case of a SimpleMissionItem which supports Launch Location display/...
static bool isTakeoffCommand(MAV_CMD command)
bool load(QTextStream &loadStream) final
static constexpr const char * canonicalName
static bool scanForItems(QmlObjectListModel *visualItems, bool flyView, PlanMasterController *masterController)
Scans the loaded items for a landing pattern complex item.
bool takeoffMissionCommand() const
bool px4Firmware() const
Definition Vehicle.h:494
void defaultHoverSpeedChanged(double hoverSpeed)
void defaultCruiseSpeedChanged(double cruiseSpeed)
QString missionFlightMode() const
Definition Vehicle.cc:2533
void _offlineVehicleTypeSettingChanged(QVariant varVehicleType)
Definition Vehicle.cc:487
QString flightMode() const
Definition Vehicle.cc:1468
bool vtol() const
Definition Vehicle.cc:1763
bool rover() const
Definition Vehicle.cc:1743
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:510
MAV_AUTOPILOT firmwareType() const
Definition Vehicle.h:427
void _offlineFirmwareTypeSettingChanged(QVariant varFirmwareType)
Definition Vehicle.cc:474
void trackFirmwareVehicleTypeChanges(void)
Definition Vehicle.cc:212
double defaultHoverSpeed() const
Definition Vehicle.h:525
void stopTrackingFirmwareVehicleTypeChanges(void)
Definition Vehicle.cc:221
bool initialPlanRequestComplete() const
Definition Vehicle.h:703
bool fixedWing() const
Definition Vehicle.cc:1738
double defaultCruiseSpeed() const
Definition Vehicle.h:524
bool armed() const
Definition Vehicle.h:449
VehicleSupports * supports()
Definition Vehicle.h:402
MissionManager * missionManager()
Definition Vehicle.h:570
void vehicleTypeChanged()
virtual int lastSequenceNumber(void) const =0
void setIsCurrentItem(bool isCurrentItem)
void setHasCurrentChildItem(bool hasCurrentChildItem)
void specifiedVehicleYawChanged(void)
virtual void setCoordinate(const QGeoCoordinate &coordinate)=0
virtual int sequenceNumber(void) const =0
virtual void applyNewAltitude(double newAltitude)=0
Adjust the altitude of the item if appropriate to the new altitude.
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)
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)
void specifiedFlightSpeedChanged(void)
void clearSimpleFlighPathSegment(void)
void currentVTOLModeChanged(void)
Signals that this item has changed the VTOL mode (MAV_CMD_DO_VTOL_TRANSITION)
virtual void setSequenceNumber(int sequenceNumber)=0
virtual ReadyForSaveState readyForSaveState(void) const
void specifiedGimbalYawChanged(void)
void amslEntryAltChanged(double alt)
void specifiedGimbalPitchChanged(void)
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 bool specifiesCoordinate(void) const =0
void exitCoordinateChanged(const QGeoCoordinate &exitCoordinate)
void additionalTimeDelayChanged(void)
virtual void save(QJsonArray &missionItems)=0
VisualMissionItem * parentItem(void)
virtual QGeoCoordinate entryCoordinate(void) const =0
virtual double editableAlt(void) const =0
bool loadGeoCoordinate(const QJsonValue &jsonValue, bool altitudeRequired, QGeoCoordinate &coordinate, QString &errorString)
void saveGeoCoordinate(const QGeoCoordinate &coordinate, bool writeAltitude, QJsonValue &jsonValue)
Saves a QGeoCoordinate as [lat, lon, alt] array (QGC plan format).
bool validateKeys(const QJsonObject &jsonObject, const QList< KeyValidateInfo > &keyInfo, QString &errorString)
Validates that all required keys are present and that listed keys have the expected type.
constexpr const char * jsonVersionKey
Definition JsonParsing.h:12
bool fuzzyCompare(double value1, double value2)
Returns true if the two values are equal or close. Correctly handles 0 and NaN values.
Definition QGCMath.cc:109
int batteriesRequired
-1 for not supported
int batteryChangePoint
-1 for not supported, 0 for not needed
static constexpr VehicleClass_t VehicleClassGeneric