QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MissionController.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QHash>
4#include <QtCore/QFile>
5#include <QtCore/QPersistentModelIndex>
6#include <QtCore/QVariant>
7#include <QtPositioning/QGeoCoordinate>
8#include <QtQmlIntegration/QtQmlIntegration>
9
11#include "QmlObjectListModel.h"
12#include "QmlObjectTreeModel.h"
13#include "QGCGeoBoundingCube.h"
15#include "QGCMAVLink.h"
16#include "MissionFlightStatus.h"
18
21class MissionItem;
22class AppSettings;
23class MissionManager;
31class Vehicle;
32
33typedef QPair<VisualMissionItem*,VisualMissionItem*> VisualItemPair;
34typedef QHash<VisualItemPair, FlightPathSegment*> FlightPathSegmentHashTable;
35
37{
38 Q_OBJECT
39 QML_ELEMENT
40 QML_UNCREATABLE("")
41 Q_MOC_INCLUDE("FlightPathSegment.h")
42 Q_MOC_INCLUDE("VisualMissionItem.h")
43 Q_MOC_INCLUDE("TakeoffMissionItem.h")
44
45public:
46 MissionController(PlanMasterController* masterController, QObject* parent = nullptr);
48
49 // Legacy alias kept for source compatibility with external code
51
53 Q_PROPERTY(QmlObjectTreeModel* visualItemsTree READ visualItemsTree CONSTANT)
54 Q_PROPERTY(QPersistentModelIndex planFileGroupIndex READ planFileGroupIndex CONSTANT)
55 Q_PROPERTY(QPersistentModelIndex defaultsGroupIndex READ defaultsGroupIndex CONSTANT)
56 Q_PROPERTY(QPersistentModelIndex missionGroupIndex READ missionGroupIndex CONSTANT)
57 Q_PROPERTY(QPersistentModelIndex fenceGroupIndex READ fenceGroupIndex CONSTANT)
58 Q_PROPERTY(QPersistentModelIndex rallyGroupIndex READ rallyGroupIndex CONSTANT)
59 Q_PROPERTY(QPersistentModelIndex transformGroupIndex READ transformGroupIndex CONSTANT)
61 Q_PROPERTY(QmlObjectListModel* directionArrows READ directionArrows CONSTANT)
62 Q_PROPERTY(QVariantList complexMissionItems READ complexMissionItems NOTIFY complexMissionItemsChanged)
63 Q_PROPERTY(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged)
64 Q_PROPERTY(bool homePositionSet READ homePositionSet NOTIFY homePositionSetChanged)
65 Q_PROPERTY(QGeoCoordinate previousCoordinate MEMBER _previousCoordinate NOTIFY planViewStateChanged)
66 Q_PROPERTY(FlightPathSegment* splitSegment MEMBER _splitSegment NOTIFY splitSegmentChanged)
67 Q_PROPERTY(double progressPct READ progressPct NOTIFY progressPctChanged)
76 Q_PROPERTY(double missionTime READ missionTime NOTIFY missionTimeChanged)
79 Q_PROPERTY(double missionHoverTime READ missionHoverTime NOTIFY missionHoverTimeChanged)
85 Q_PROPERTY(bool onlyInsertTakeoffValid MEMBER _onlyInsertTakeoffValid NOTIFY planViewStateChanged)
86 Q_PROPERTY(bool isInsertTakeoffValid MEMBER _isInsertTakeoffValid NOTIFY planViewStateChanged)
87 Q_PROPERTY(bool isInsertLandValid MEMBER _isInsertLandValid NOTIFY planViewStateChanged)
88 Q_PROPERTY(bool hasLandItem MEMBER _hasLandItem NOTIFY hasLandItemChanged)
90 Q_PROPERTY(bool isROIActive MEMBER _isROIActive NOTIFY planViewStateChanged)
91 Q_PROPERTY(bool isROIBeginCurrentItem MEMBER _isROIBeginCurrentItem NOTIFY planViewStateChanged)
92 Q_PROPERTY(bool flyThroughCommandsAllowed MEMBER _flyThroughCommandsAllowed NOTIFY planViewStateChanged)
93 Q_PROPERTY(double minAMSLAltitude MEMBER _minAMSLAltitude NOTIFY minAMSLAltitudeChanged)
94 Q_PROPERTY(double maxAMSLAltitude MEMBER _maxAMSLAltitude NOTIFY maxAMSLAltitudeChanged)
95
98
99 Q_INVOKABLE void removeVisualItem(int viIndex);
100
102 Q_INVOKABLE int visualItemIndexForObject(QObject* object) const;
103
105 Q_INVOKABLE void setHomePosition(QGeoCoordinate coordinate);
106
112 Q_INVOKABLE VisualMissionItem* insertSimpleMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem = false);
113
119 Q_INVOKABLE VisualMissionItem* insertTakeoffItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem = false);
120
126 Q_INVOKABLE VisualMissionItem* insertLandItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem = false);
127
133 Q_INVOKABLE VisualMissionItem* insertROIMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem = false);
134
139 Q_INVOKABLE VisualMissionItem* insertCancelROIMissionItem(int visualItemIndex, bool makeCurrentItem = false);
140
147 Q_INVOKABLE VisualMissionItem* insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int visualItemIndex, bool makeCurrentItem = false);
148
156 Q_INVOKABLE VisualMissionItem* insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int visualItemIndex, bool makeCurrentItem = false);
157
158 Q_INVOKABLE void resumeMission(int resumeIndex);
159
161 Q_INVOKABLE void applyDefaultMissionAltitude(void);
162
166 Q_INVOKABLE void setCurrentPlanViewSeqNum(int sequenceNumber, bool force);
167
176 Q_INVOKABLE void repositionMission(const QGeoCoordinate& newHome,
177 bool repositionTakeoffItems = true,
178 bool repositionLandingItems = true);
179
189 Q_INVOKABLE void offsetMission(double eastMeters,
190 double northMeters,
191 double upMeters = 0.0,
192 bool offsetTakeoffItems = false,
193 bool offsetLandingItems = false);
194
205 Q_INVOKABLE void rotateMission(double degreesCW,
206 bool rotateTakeoffItems = false,
207 bool rotateLandingItems = false);
208
210 SendToVehiclePreCheckStateOk, // Ok to send plan to vehicle
211 SendToVehiclePreCheckStateNoActiveVehicle, // There is no active vehicle
212 SendToVehiclePreCheckStateFirwmareVehicleMismatch, // Firmware/Vehicle type for plan mismatch with actual vehicle
213 SendToVehiclePreCheckStateActiveMission, // Vehicle is currently flying a mission
214 };
216
218
222 int readyForSaveState(void) const;
223
225 static void sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems);
226
227 bool loadTextFile(QFile& file, QString& errorString);
228
229 QGCGeoBoundingCube* travelBoundingCube () { return &_travelBoundingCube; }
230 QGeoCoordinate takeoffCoordinate () { return _takeoffCoordinate; }
231
232 // Overrides from PlanElementController
233 bool supported (void) const final { return true; }
234 void start (bool flyView) final;
235 void save (QJsonObject& json) final;
236 bool load (const QJsonObject& json, QString& errorString) final;
237 void loadFromVehicle (void) final;
238 void sendToVehicle (void) final;
239 void removeAll (void) final;
240 void removeAllFromVehicle (void) final;
241 bool syncInProgress (void) const final;
242 bool dirty (void) const final;
243 void setDirty (bool dirty) final;
244 bool containsItems (void) const final;
245 bool showPlanFromManagerVehicle (void) final;
246
247 // Create KML file
248 void addMissionToKML(KMLPlanDomDocument& planKML);
249
250 // Property accessors
251
252 QmlObjectListModel* visualItems (void) { return _visualItems; }
253 QmlObjectTreeModel* visualItemsTree (void) { return &_visualItemsTree; }
254 QPersistentModelIndex planFileGroupIndex (void) const { return _planFileGroupIndex; }
255 QPersistentModelIndex defaultsGroupIndex (void) const { return _defaultsGroupIndex; }
256 QPersistentModelIndex missionGroupIndex (void) const { return _missionGroupIndex; }
257 QPersistentModelIndex fenceGroupIndex (void) const { return _fenceGroupIndex; }
258 QPersistentModelIndex rallyGroupIndex (void) const { return _rallyGroupIndex; }
259 QPersistentModelIndex transformGroupIndex (void) const { return _transformGroupIndex; }
260 QmlObjectListModel* simpleFlightPathSegments (void) { return &_simpleFlightPathSegments; }
261 QmlObjectListModel* directionArrows (void) { return &_directionArrows; }
262 QVariantList complexMissionItems (void) const;
263 QGeoCoordinate plannedHomePosition (void) const;
264 bool homePositionSet (void) const;
265 VisualMissionItem* currentPlanViewItem (void) const { return _currentPlanViewItem; }
266 TakeoffMissionItem* takeoffMissionItem (void) const { return _takeoffMissionItem; }
267 double progressPct (void) const { return _progressPct; }
268 bool isInsertTakeoffValid (void) const;
269 bool multipleLandPatternsAllowed (void) const;
270 double minAMSLAltitude (void) const { return _minAMSLAltitude; }
271 double maxAMSLAltitude (void) const { return _maxAMSLAltitude; }
272
273 int currentMissionIndex (void) const;
274 int resumeMissionIndex (void) const;
275 int currentPlanViewSeqNum (void) const { return _currentPlanViewSeqNum; }
276 int currentPlanViewVIIndex (void) const { return _currentPlanViewVIIndex; }
277
278 double missionTotalDistance (void) const { return _missionFlightStatus.totalDistance; }
279 double missionPlannedDistance (void) const { return _missionFlightStatus.plannedDistance; }
280 double missionTime (void) const { return _missionFlightStatus.totalTime; }
281 double missionHoverDistance (void) const { return _missionFlightStatus.hoverDistance; }
282 double missionHoverTime (void) const { return _missionFlightStatus.hoverTime; }
283 double missionCruiseDistance (void) const { return _missionFlightStatus.cruiseDistance; }
284 double missionCruiseTime (void) const { return _missionFlightStatus.cruiseTime; }
285 double missionMaxTelemetry (void) const { return _missionFlightStatus.maxTelemetryDistance; }
286
287 int batteryChangePoint (void) const { return _missionFlightStatus.batteryChangePoint; }
288 int batteriesRequired (void) const { return _missionFlightStatus.batteriesRequired; }
289
290 bool isFirstLandingComplexItem (const LandingComplexItem* item) const;
291 bool isEmpty (void) const;
292
296
297 // Top-level group row indices in _visualItemsTree (must match _setupTreeModel order)
298 static constexpr int kPlanFileGroupRow = 0;
299 static constexpr int kDefaultsGroupRow = 1;
300 static constexpr int kMissionGroupRow = 2;
301 static constexpr int kFenceGroupRow = 3;
302 static constexpr int kRallyGroupRow = 4;
303 static constexpr int kTransformGroupRow = 5;
304 static constexpr int kGroupCount = 6;
305
306signals:
307 void visualItemsReset (void);
339
340private slots:
341 void _newMissionItemsAvailableFromVehicle (bool removeAllRequested);
342 void _itemCommandChanged (void);
343 void _inProgressChanged (bool inProgress);
344 void _currentMissionIndexChanged (int sequenceNumber);
345 void _recalcFlightPathSegments (void);
346 void _recalcMissionFlightStatus (void);
347 void _progressPctChanged (double progressPct);
348 void _visualItemsDirtyChanged (bool dirty);
349 void _managerSendComplete (bool error);
350 void _managerRemoveAllComplete (bool error);
351 void _updateTimeout (void);
352 void _complexBoundingBoxChanged (void);
353 void _recalcAll (void);
354 void _managerVehicleChanged (Vehicle* managerVehicle);
355 void _forceRecalcOfAllowedBits (void);
356 // Incremental tree model sync slots
357 void _syncTreeMissionItemsInserted (const QModelIndex& parent, int first, int last);
358 void _syncTreeMissionItemsAboutToBeRemoved (const QModelIndex& parent, int first, int last);
359 void _syncTreeMissionItemsReset (void);
360 void _syncTreeRallyPointsInserted (const QModelIndex& parent, int first, int last);
361 void _syncTreeRallyPointsAboutToBeRemoved (const QModelIndex& parent, int first, int last);
362 void _syncTreeRallyPointsRemoved (const QModelIndex& parent, int first, int last);
363
364 void _syncTreeRallyPointsReset (void);
365private:
366 void _init (void);
367 void _setupTreeModel (void);
368 void _recalcSequence (void);
369 void _recalcChildItems (void);
370 void _recalcAllWithCoordinate (const QGeoCoordinate& coordinate);
371 void _setupNewVisualItems (QmlObjectListModel* newItems = nullptr);
372 void _initAllVisualItems (void);
373 void _deinitAllVisualItems (void);
374 void _initVisualItem (VisualMissionItem* item);
375 void _deinitVisualItem (VisualMissionItem* item);
376 void _setupActiveVehicle (Vehicle* activeVehicle, bool forceLoadFromVehicle);
377 bool _findPreviousAltitude (int newIndex, double* prevAltitude, QGroundControlQmlGlobal::AltitudeFrame* prevAltFrame);
378 MissionSettingsItem* _addMissionSettings (QmlObjectListModel* visualItems);
379 bool _loadJsonMissionFileV2 (const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString);
380 bool _loadTextMissionFile (QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString);
381 int _nextSequenceNumber (void);
382 void _scanForAdditionalSettings (QmlObjectListModel* visualItems, PlanMasterController* masterController);
383 void _setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate);
384 void _resetMissionFlightStatus (void);
385 void _initLoadedVisualItems (QmlObjectListModel* loadedVisualItems);
386 FlightPathSegment* _addFlightPathSegment (FlightPathSegmentHashTable& prevItemPairHashTable, VisualItemPair& pair, bool mavlinkTerrainFrame);
387 VisualMissionItem* _insertSimpleMissionItemWorker (QGeoCoordinate coordinate, MAV_CMD command, int visualItemIndex, bool makeCurrentItem);
388 void _insertComplexMissionItemWorker (const QGeoCoordinate& mapCenterCoordinate, ComplexMissionItem* complexItem, int visualItemIndex, bool makeCurrentItem);
389 bool _isROIBeginItem (SimpleMissionItem* simpleItem);
390 bool _isROICancelItem (SimpleMissionItem* simpleItem);
391 FlightPathSegment* _createFlightPathSegmentWorker (VisualItemPair& pair, bool mavlinkTerrainFrame);
392 void _allItemsRemoved (void);
393 void _firstItemAdded (void);
394
395 static double _normalizeLat (double lat);
396 static double _normalizeLon (double lon);
397 static bool _convertToMissionItems (QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent);
398
399private:
400 Vehicle* _controllerVehicle = nullptr;
401 Vehicle* _managerVehicle = nullptr;
402 MissionManager* _missionManager = nullptr;
403 QmlObjectListModel* _visualItems = nullptr;
404 QPersistentModelIndex _planFileGroupIndex;
405 QPersistentModelIndex _defaultsGroupIndex;
406 QPersistentModelIndex _missionGroupIndex;
407 QPersistentModelIndex _fenceGroupIndex;
408 QPersistentModelIndex _rallyGroupIndex;
409 QPersistentModelIndex _transformGroupIndex;
410 QObject _planFileGroupNode;
411 QObject _planFileInfoMarker;
412 QObject _defaultsGroupNode;
413 QObject _defaultsInfoMarker;
414 QObject _missionItemsGroupNode;
415 QObject _fenceGroupNode;
416 QObject _rallyGroupNode;
417 QObject _transformGroupNode;
418 QObject _fenceEditorMarker;
419 QObject _rallyHeaderMarker;
420 QObject _transformEditorMarker;
421 QmlObjectTreeModel _visualItemsTree; // Must be declared after group nodes so it's destroyed first
422 MissionSettingsItem* _settingsItem = nullptr;
423 PlanViewSettings* _planViewSettings = nullptr;
424 QmlObjectListModel _simpleFlightPathSegments;
425 QmlObjectListModel _directionArrows;
426 FlightPathSegmentHashTable _flightPathSegmentHashTable;
427 bool _firstItemsFromVehicle = false;
428 bool _itemsRequested = false;
429 bool _inRecalcSequence = false;
430 MissionFlightStatusCalculator _flightStatusCalc;
431 MissionFlightStatus_t _missionFlightStatus;
432 AppSettings* _appSettings = nullptr;
433 double _progressPct = 0;
434 int _currentPlanViewSeqNum = -1;
435 int _currentPlanViewVIIndex = -1;
436 VisualMissionItem* _currentPlanViewItem = nullptr;
437 TakeoffMissionItem* _takeoffMissionItem = nullptr;
438 QTimer _updateTimer;
439 QGCGeoBoundingCube _travelBoundingCube;
440 QGeoCoordinate _takeoffCoordinate;
441 QGeoCoordinate _previousCoordinate;
442 FlightPathSegment* _splitSegment = nullptr;
443 bool _delayedSplitSegmentUpdate = false;
444 bool _onlyInsertTakeoffValid = true;
445 bool _isInsertTakeoffValid = true;
446 bool _isInsertLandValid = false;
447 bool _hasLandItem = false;
448 bool _isROIActive = false;
449 bool _flyThroughCommandsAllowed = false;
450 bool _isROIBeginCurrentItem = false;
451 double _minAMSLAltitude = 0;
452 double _maxAMSLAltitude = 0;
453 bool _missionContainsVTOLTakeoff = false;
454
456
457 static constexpr const char* _settingsGroup = "MissionController";
458 static constexpr const char* _jsonItemsKey = "items";
459 static constexpr const char* _jsonPlannedHomePositionKey = "plannedHomePosition";
460 static constexpr const char* _jsonFirmwareTypeKey = "firmwareType";
461 static constexpr const char* _jsonVehicleTypeKey = "vehicleType";
462 static constexpr const char* _jsonCruiseSpeedKey = "cruiseSpeed";
463 static constexpr const char* _jsonHoverSpeedKey = "hoverSpeed";
464 static constexpr const char* _jsonParamsKey = "params";
465 static constexpr const char* _jsonGlobalPlanAltitudeModeKey = "globalPlanAltitudeMode";
466
467 static constexpr int _missionFileVersion = 2;
468};
QPair< VisualMissionItem *, VisualMissionItem * > VisualItemPair
QHash< VisualItemPair, FlightPathSegment * > FlightPathSegmentHashTable
QString errorString
Error error
Application Settings.
Definition AppSettings.h:10
Used to convert a Plan to a KML document.
void minAMSLAltitudeChanged(double minAMSLAltitude)
Q_INVOKABLE void resumeMission(int resumeIndex)
static constexpr int kDefaultsGroupRow
double missionHoverDistance(void) const
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.
VisualMissionItem * currentPlanViewItem(void) const
bool showPlanFromManagerVehicle(void) final
Q_INVOKABLE SendToVehiclePreCheckState sendToVehiclePreCheck(void)
bool dirty(void) const final
static constexpr int kMissionGroupRow
Q_INVOKABLE VisualMissionItem * insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int visualItemIndex, bool makeCurrentItem=false)
QmlObjectTreeModel * visualItemsTree(void)
void batteriesRequiredChanged(int batteriesRequired)
double missionTime(void) const
bool loadTextFile(QFile &file, QString &errorString)
QmlObjectListModel * directionArrows(void)
void multipleLandPatternsAllowedChanged(void)
double minAMSLAltitude(void) const
double missionPlannedDistance(void) const
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)
double maxAMSLAltitude(void) const
void maxAMSLAltitudeChanged(double maxAMSLAltitude)
void removeAllFromVehicle(void) final
void homePositionSetChanged(void)
void recalcTerrainProfile(void)
void missionPlannedDistanceChanged(double missionPlannedDistance)
void missionTotalDistanceChanged(double missionTotalDistance)
QPersistentModelIndex planFileGroupIndex(void) const
void hasLandItemChanged(void)
void _recalcFlightPathSegmentsSignal(void)
QPersistentModelIndex fenceGroupIndex(void) const
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
double missionMaxTelemetry(void) const
void splitSegmentChanged(void)
Q_INVOKABLE void repositionMission(const QGeoCoordinate &newHome, bool repositionTakeoffItems=true, bool repositionLandingItems=true)
void resumeMissionReady(void)
@ SendToVehiclePreCheckStateFirwmareVehicleMismatch
void batteryChangePointChanged(int batteryChangePoint)
void takeoffMissionItemChanged(void)
Q_INVOKABLE void rotateMission(double degreesCW, bool rotateTakeoffItems=false, bool rotateLandingItems=false)
static constexpr int kGroupCount
void addMissionToKML(KMLPlanDomDocument &planKML)
void _recalcMissionFlightStatusSignal(void)
int batteriesRequired(void) const
-1 for not supported
void missionHoverDistanceChanged(double missionHoverDistance)
static constexpr int kFenceGroupRow
bool syncInProgress(void) const final
QPersistentModelIndex defaultsGroupIndex(void) const
TakeoffMissionItem * takeoffMissionItem(void) const
static constexpr int kRallyGroupRow
void sendToVehicle(void) final
void resumeMissionIndexChanged(void)
void currentMissionIndexChanged(int currentMissionIndex)
int batteryChangePoint(void) const
-1 for not supported, 0 for not needed
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)
int currentPlanViewVIIndex(void) const
void save(QJsonObject &json) final
double missionCruiseDistance(void) const
Q_INVOKABLE VisualMissionItem * insertSimpleMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
void missionHoverTimeChanged(void)
bool isFirstLandingComplexItem(const LandingComplexItem *item) const
QGeoCoordinate plannedHomePosition(void) const
QPersistentModelIndex transformGroupIndex(void) const
bool homePositionSet(void) const
bool containsItems(void) const final
void progressPctChanged(double progressPct)
void missionCruiseTimeChanged(void)
QPersistentModelIndex missionGroupIndex(void) const
QGroundControlQmlGlobal::AltitudeFrame globalAltitudeFrame(void)
int readyForSaveState(void) const
static constexpr int kPlanFileGroupRow
QGroundControlQmlGlobal::AltitudeFrame globalAltitudeFrameDefault(void)
int currentPlanViewSeqNum(void) const
void removeAll(void) final
Removes all from controller only.
::MissionFlightStatus_t MissionFlightStatus_t
Default to use for newly created items.
void visualItemsReset(void)
void missionBoundingCubeChanged(void)
bool isInsertTakeoffValid(void) const
double missionCruiseTime(void) const
QVariantList complexMissionItems(void) const
void missionTimeChanged(void)
QPersistentModelIndex rallyGroupIndex(void) const
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.
QGCGeoBoundingCube * travelBoundingCube()
void planViewStateChanged(void)
All plan-view properties are recomputed together in setCurrentPlanViewSeqNum, so one signal covers th...
void globalAltitudeFrameChanged(void)
void missionCruiseDistanceChanged(double missionCruiseDistance)
double missionTotalDistance(void) const
void resumeMissionUploadFail(void)
void loadFromVehicle(void) final
double missionHoverTime(void) const
QmlObjectListModel * simpleFlightPathSegments(void)
bool supported(void) const final
true: controller is waiting for the current load to complete
Q_INVOKABLE VisualMissionItem * insertCancelROIMissionItem(int visualItemIndex, bool makeCurrentItem=false)
static constexpr int kTransformGroupRow
int resumeMissionIndex(void) const
Q_INVOKABLE VisualMissionItem * insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int visualItemIndex, bool makeCurrentItem=false)
QmlObjectListModel * visualItems(void)
Computes mission flight status (distances, times, battery, altitude range)
This is the abstract base clas for Plan Element controllers.
PlanMasterController * masterController(void)
Master controller for mission, fence, rally.
A tree model for QObject* items, usable from both C++ and QML.
A SimpleMissionItem is used to represent a single MissionItem to the ui.
Takeoff mission item is a special case of a SimpleMissionItem which supports Launch Location display/...
int batteriesRequired
-1 for not supported
int batteryChangePoint
-1 for not supported, 0 for not needed