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/QLoggingCategory>
6#include <QtCore/QPersistentModelIndex>
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
17Q_DECLARE_LOGGING_CATEGORY(MissionControllerLog)
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 typedef struct {
53 double totalTime;
55 double hoverTime;
57 double cruiseTime;
59 double hoverAmps;
60 double cruiseAmps;
66 double vehicleYaw;
67 double gimbalYaw;
68 double gimbalPitch;
69 // The following values are the state prior to executing this item
72 double hoverSpeed;
73 double vehicleSpeed;
75
78 Q_PROPERTY(QPersistentModelIndex planFileGroupIndex READ planFileGroupIndex CONSTANT)
79 Q_PROPERTY(QPersistentModelIndex defaultsGroupIndex READ defaultsGroupIndex CONSTANT)
80 Q_PROPERTY(QPersistentModelIndex missionGroupIndex READ missionGroupIndex CONSTANT)
81 Q_PROPERTY(QPersistentModelIndex fenceGroupIndex READ fenceGroupIndex CONSTANT)
82 Q_PROPERTY(QPersistentModelIndex rallyGroupIndex READ rallyGroupIndex CONSTANT)
86 Q_PROPERTY(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged)
87 Q_PROPERTY(QGeoCoordinate previousCoordinate MEMBER _previousCoordinate NOTIFY previousCoordinateChanged)
88 Q_PROPERTY(FlightPathSegment* splitSegment MEMBER _splitSegment NOTIFY splitSegmentChanged)
89 Q_PROPERTY(double progressPct READ progressPct NOTIFY progressPctChanged)
99 Q_PROPERTY(double missionTime READ missionTime NOTIFY missionTimeChanged)
102 Q_PROPERTY(double missionHoverTime READ missionHoverTime NOTIFY missionHoverTimeChanged)
111 Q_PROPERTY(bool onlyInsertTakeoffValid MEMBER _onlyInsertTakeoffValid NOTIFY onlyInsertTakeoffValidChanged)
112 Q_PROPERTY(bool isInsertTakeoffValid MEMBER _isInsertTakeoffValid NOTIFY isInsertTakeoffValidChanged)
113 Q_PROPERTY(bool isInsertLandValid MEMBER _isInsertLandValid NOTIFY isInsertLandValidChanged)
114 Q_PROPERTY(bool hasLandItem MEMBER _hasLandItem NOTIFY hasLandItemChanged)
116 Q_PROPERTY(bool isROIActive MEMBER _isROIActive NOTIFY isROIActiveChanged)
117 Q_PROPERTY(bool isROIBeginCurrentItem MEMBER _isROIBeginCurrentItem NOTIFY isROIBeginCurrentItemChanged)
118 Q_PROPERTY(bool flyThroughCommandsAllowed MEMBER _flyThroughCommandsAllowed NOTIFY flyThroughCommandsAllowedChanged)
119 Q_PROPERTY(double minAMSLAltitude MEMBER _minAMSLAltitude NOTIFY minAMSLAltitudeChanged)
120 Q_PROPERTY(double maxAMSLAltitude MEMBER _maxAMSLAltitude NOTIFY maxAMSLAltitudeChanged)
121
124
125 Q_INVOKABLE void removeVisualItem(int viIndex);
126
128 Q_INVOKABLE int visualItemIndexForObject(QObject* object) const;
129
135 Q_INVOKABLE VisualMissionItem* insertSimpleMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem = false);
136
142 Q_INVOKABLE VisualMissionItem* insertTakeoffItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem = false);
143
149 Q_INVOKABLE VisualMissionItem* insertLandItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem = false);
150
156 Q_INVOKABLE VisualMissionItem* insertROIMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem = false);
157
162 Q_INVOKABLE VisualMissionItem* insertCancelROIMissionItem(int visualItemIndex, bool makeCurrentItem = false);
163
170 Q_INVOKABLE VisualMissionItem* insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int visualItemIndex, bool makeCurrentItem = false);
171
179 Q_INVOKABLE VisualMissionItem* insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int visualItemIndex, bool makeCurrentItem = false);
180
181 Q_INVOKABLE void resumeMission(int resumeIndex);
182
184 Q_INVOKABLE void applyDefaultMissionAltitude(void);
185
189 Q_INVOKABLE void setCurrentPlanViewSeqNum(int sequenceNumber, bool force);
190
199 Q_INVOKABLE void repositionMission(const QGeoCoordinate& newHome,
200 bool repositionTakeoffItems = true,
201 bool repositionLandingItems = true);
202
214 Q_INVOKABLE void offsetMission(double eastMeters,
215 double northMeters,
216 double upMeters = 0.0,
217 bool offsetTakeoffItems = false,
218 bool offsetLandingItems = false);
219
230 Q_INVOKABLE void rotateMission(double degreesCW,
231 bool rotateTakeoffItems = false,
232 bool rotateLandingItems = false);
233
235 SendToVehiclePreCheckStateOk, // Ok to send plan to vehicle
236 SendToVehiclePreCheckStateNoActiveVehicle, // There is no active vehicle
237 SendToVehiclePreCheckStateFirwmareVehicleMismatch, // Firmware/Vehicle type for plan mismatch with actual vehicle
238 SendToVehiclePreCheckStateActiveMission, // Vehicle is currently flying a mission
239 };
241
243
247 int readyForSaveState(void) const;
248
250 static void sendItemsToVehicle(Vehicle* vehicle, QmlObjectListModel* visualMissionItems);
251
252 bool loadTextFile(QFile& file, QString& errorString);
253
254 QGCGeoBoundingCube* travelBoundingCube () { return &_travelBoundingCube; }
255 QGeoCoordinate takeoffCoordinate () { return _takeoffCoordinate; }
256
257 // Overrides from PlanElementController
258 bool supported (void) const final { return true; }
259 void start (bool flyView) final;
260 void save (QJsonObject& json) final;
261 bool load (const QJsonObject& json, QString& errorString) final;
262 void loadFromVehicle (void) final;
263 void sendToVehicle (void) final;
264 void removeAll (void) final;
265 void removeAllFromVehicle (void) final;
266 bool syncInProgress (void) const final;
267 bool dirty (void) const final;
268 void setDirty (bool dirty) final;
269 bool containsItems (void) const final;
270 bool showPlanFromManagerVehicle (void) final;
271
272 // Create KML file
273 void addMissionToKML(KMLPlanDomDocument& planKML);
274
275 // Property accessors
276
277 QmlObjectListModel* visualItems (void) { return _visualItems; }
278 QmlObjectTreeModel* visualItemsTree (void) { return &_visualItemsTree; }
279 QPersistentModelIndex planFileGroupIndex (void) const { return _planFileGroupIndex; }
280 QPersistentModelIndex defaultsGroupIndex (void) const { return _defaultsGroupIndex; }
281 QPersistentModelIndex missionGroupIndex (void) const { return _missionGroupIndex; }
282 QPersistentModelIndex fenceGroupIndex (void) const { return _fenceGroupIndex; }
283 QPersistentModelIndex rallyGroupIndex (void) const { return _rallyGroupIndex; }
284 QmlObjectListModel* simpleFlightPathSegments (void) { return &_simpleFlightPathSegments; }
285 QmlObjectListModel* directionArrows (void) { return &_directionArrows; }
286 QStringList complexMissionItemNames (void) const;
287 QGeoCoordinate plannedHomePosition (void) const;
288 VisualMissionItem* currentPlanViewItem (void) const { return _currentPlanViewItem; }
289 TakeoffMissionItem* takeoffMissionItem (void) const { return _takeoffMissionItem; }
290 double progressPct (void) const { return _progressPct; }
291 QString surveyComplexItemName (void) const;
292 QString corridorScanComplexItemName (void) const;
293 QString structureScanComplexItemName(void) const;
294 bool isInsertTakeoffValid (void) const;
295 bool multipleLandPatternsAllowed (void) const;
296 double minAMSLAltitude (void) const { return _minAMSLAltitude; }
297 double maxAMSLAltitude (void) const { return _maxAMSLAltitude; }
298
299 int missionItemCount (void) const { return _missionItemCount; }
300 int currentMissionIndex (void) const;
301 int resumeMissionIndex (void) const;
302 int currentPlanViewSeqNum (void) const { return _currentPlanViewSeqNum; }
303 int currentPlanViewVIIndex (void) const { return _currentPlanViewVIIndex; }
304
305 double missionTotalDistance (void) const { return _missionFlightStatus.totalDistance; }
306 double missionPlannedDistance (void) const { return _missionFlightStatus.plannedDistance; }
307 double missionTime (void) const { return _missionFlightStatus.totalTime; }
308 double missionHoverDistance (void) const { return _missionFlightStatus.hoverDistance; }
309 double missionHoverTime (void) const { return _missionFlightStatus.hoverTime; }
310 double missionCruiseDistance (void) const { return _missionFlightStatus.cruiseDistance; }
311 double missionCruiseTime (void) const { return _missionFlightStatus.cruiseTime; }
312 double missionMaxTelemetry (void) const { return _missionFlightStatus.maxTelemetryDistance; }
313
314 int batteryChangePoint (void) const { return _missionFlightStatus.batteryChangePoint; }
315 int batteriesRequired (void) const { return _missionFlightStatus.batteriesRequired; }
316
317 bool isFirstLandingComplexItem (const LandingComplexItem* item) const;
318 bool isEmpty (void) const;
319
323
324 // Top-level group row indices in _visualItemsTree (must match _setupTreeModel order)
325 static constexpr int kPlanFileGroupRow = 0;
326 static constexpr int kDefaultsGroupRow = 1;
327 static constexpr int kMissionGroupRow = 2;
328 static constexpr int kFenceGroupRow = 3;
329 static constexpr int kRallyGroupRow = 4;
330 static constexpr int kGroupCount = 5;
331
332signals:
374
375private slots:
376 void _newMissionItemsAvailableFromVehicle (bool removeAllRequested);
377 void _itemCommandChanged (void);
378 void _inProgressChanged (bool inProgress);
379 void _currentMissionIndexChanged (int sequenceNumber);
380 void _recalcFlightPathSegments (void);
381 void _recalcMissionFlightStatus (void);
382 void _updateContainsItems (void);
383 void _progressPctChanged (double progressPct);
384 void _visualItemsDirtyChanged (bool dirty);
385 void _managerSendComplete (bool error);
386 void _managerRemoveAllComplete (bool error);
387 void _updateTimeout (void);
388 void _complexBoundingBoxChanged (void);
389 void _recalcAll (void);
390 void _managerVehicleChanged (Vehicle* managerVehicle);
391 void _forceRecalcOfAllowedBits (void);
392 // Incremental tree model sync slots
393 void _onMissionItemsInserted (const QModelIndex& parent, int first, int last);
394 void _onMissionItemsAboutToBeRemoved (const QModelIndex& parent, int first, int last);
395 void _onMissionItemsReset (void);
396 void _onRallyPointsInserted (const QModelIndex& parent, int first, int last);
397 void _onRallyPointsAboutToBeRemoved (const QModelIndex& parent, int first, int last);
398 void _onRallyPointsReset (void);
399private:
400 void _init (void);
401 void _setupTreeModel (void);
402 void _recalcSequence (void);
403 void _recalcChildItems (void);
404 void _recalcAllWithCoordinate (const QGeoCoordinate& coordinate);
405 void _recalcROISpecialVisuals (void);
406 void _initAllVisualItems (void);
407 void _deinitAllVisualItems (void);
408 void _initVisualItem (VisualMissionItem* item);
409 void _deinitVisualItem (VisualMissionItem* item);
410 void _setupActiveVehicle (Vehicle* activeVehicle, bool forceLoadFromVehicle);
411 void _calcPrevWaypointValues (VisualMissionItem* currentItem, VisualMissionItem* prevItem, double* azimuth, double* distance, double* altDifference);
412 bool _findPreviousAltitude (int newIndex, double* prevAltitude, QGroundControlQmlGlobal::AltMode* prevAltMode);
413 MissionSettingsItem* _addMissionSettings (QmlObjectListModel* visualItems);
414 void _centerHomePositionOnMissionItems (QmlObjectListModel* visualItems);
415 bool _loadJsonMissionFile (const QByteArray& bytes, QmlObjectListModel* visualItems, QString& errorString);
416 bool _loadJsonMissionFileV1 (const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString);
417 bool _loadJsonMissionFileV2 (const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString);
418 bool _loadTextMissionFile (QTextStream& stream, QmlObjectListModel* visualItems, QString& errorString);
419 int _nextSequenceNumber (void);
420 void _scanForAdditionalSettings (QmlObjectListModel* visualItems, PlanMasterController* masterController);
421 void _setPlannedHomePositionFromFirstCoordinate(const QGeoCoordinate& clickCoordinate);
422 void _resetMissionFlightStatus (void);
423 void _addHoverTime (double hoverTime, double hoverDistance, int waypointIndex);
424 void _addCruiseTime (double cruiseTime, double cruiseDistance, int wayPointIndex);
425 void _updateBatteryInfo (int waypointIndex);
426 bool _loadItemsFromJson (const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString);
427 void _initLoadedVisualItems (QmlObjectListModel* loadedVisualItems);
428 FlightPathSegment* _addFlightPathSegment (FlightPathSegmentHashTable& prevItemPairHashTable, VisualItemPair& pair, bool mavlinkTerrainFrame);
429 void _addTimeDistance (bool vtolInHover, double hoverTime, double cruiseTime, double extraTime, double distance, int seqNum);
430 VisualMissionItem* _insertSimpleMissionItemWorker (QGeoCoordinate coordinate, MAV_CMD command, int visualItemIndex, bool makeCurrentItem);
431 void _insertComplexMissionItemWorker (const QGeoCoordinate& mapCenterCoordinate, ComplexMissionItem* complexItem, int visualItemIndex, bool makeCurrentItem);
432 bool _isROIBeginItem (SimpleMissionItem* simpleItem);
433 bool _isROICancelItem (SimpleMissionItem* simpleItem);
434 FlightPathSegment* _createFlightPathSegmentWorker (VisualItemPair& pair, bool mavlinkTerrainFrame);
435 void _allItemsRemoved (void);
436 void _firstItemAdded (void);
437
438 static double _calcDistanceToHome (VisualMissionItem* currentItem, VisualMissionItem* homeItem);
439 static double _normalizeLat (double lat);
440 static double _normalizeLon (double lon);
441 static bool _convertToMissionItems (QmlObjectListModel* visualMissionItems, QList<MissionItem*>& rgMissionItems, QObject* missionItemParent);
442
443private:
444 Vehicle* _controllerVehicle = nullptr;
445 Vehicle* _managerVehicle = nullptr;
446 MissionManager* _missionManager = nullptr;
447 int _missionItemCount = 0;
448 QmlObjectListModel* _visualItems = nullptr;
449 QPersistentModelIndex _planFileGroupIndex;
450 QPersistentModelIndex _defaultsGroupIndex;
451 QPersistentModelIndex _missionGroupIndex;
452 QPersistentModelIndex _fenceGroupIndex;
453 QPersistentModelIndex _rallyGroupIndex;
454 QObject _planFileGroupNode;
455 QObject _planFileInfoMarker;
456 QObject _defaultsGroupNode;
457 QObject _defaultsInfoMarker;
458 QObject _missionItemsGroupNode;
459 QObject _fenceGroupNode;
460 QObject _rallyGroupNode;
461 QObject _fenceEditorMarker;
462 QObject _rallyHeaderMarker;
463 QmlObjectTreeModel _visualItemsTree; // Must be declared after group nodes so it's destroyed first
464 MissionSettingsItem* _settingsItem = nullptr;
465 PlanViewSettings* _planViewSettings = nullptr;
466 QmlObjectListModel _simpleFlightPathSegments;
467 QmlObjectListModel _directionArrows;
468 FlightPathSegmentHashTable _flightPathSegmentHashTable;
469 bool _firstItemsFromVehicle = false;
470 bool _itemsRequested = false;
471 bool _inRecalcSequence = false;
472 MissionFlightStatus_t _missionFlightStatus;
473 AppSettings* _appSettings = nullptr;
474 double _progressPct = 0;
475 int _currentPlanViewSeqNum = -1;
476 int _currentPlanViewVIIndex = -1;
477 VisualMissionItem* _currentPlanViewItem = nullptr;
478 TakeoffMissionItem* _takeoffMissionItem = nullptr;
479 QTimer _updateTimer;
480 QGCGeoBoundingCube _travelBoundingCube;
481 QGeoCoordinate _takeoffCoordinate;
482 QGeoCoordinate _previousCoordinate;
483 FlightPathSegment* _splitSegment = nullptr;
484 bool _delayedSplitSegmentUpdate = false;
485 bool _onlyInsertTakeoffValid = true;
486 bool _isInsertTakeoffValid = true;
487 bool _isInsertLandValid = false;
488 bool _hasLandItem = false;
489 bool _isROIActive = false;
490 bool _flyThroughCommandsAllowed = false;
491 bool _isROIBeginCurrentItem = false;
492 double _minAMSLAltitude = 0;
493 double _maxAMSLAltitude = 0;
494 bool _missionContainsVTOLTakeoff = false;
495
497
498 static constexpr const char* _settingsGroup = "MissionController";
499 static constexpr const char* _jsonFileTypeValue = "Mission";
500 static constexpr const char* _jsonItemsKey = "items";
501 static constexpr const char* _jsonPlannedHomePositionKey = "plannedHomePosition";
502 static constexpr const char* _jsonFirmwareTypeKey = "firmwareType";
503 static constexpr const char* _jsonVehicleTypeKey = "vehicleType";
504 static constexpr const char* _jsonCruiseSpeedKey = "cruiseSpeed";
505 static constexpr const char* _jsonHoverSpeedKey = "hoverSpeed";
506 static constexpr const char* _jsonParamsKey = "params";
507 static constexpr const char* _jsonGlobalPlanAltitudeModeKey = "globalPlanAltitudeMode";
508
509 // Deprecated V1 format keys
510 static constexpr const char* _jsonComplexItemsKey = "complexItems";
511 static constexpr const char* _jsonMavAutopilotKey = "MAV_AUTOPILOT";
512
513 static constexpr int _missionFileVersion = 2;
514};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
QPair< VisualMissionItem *, VisualMissionItem * > VisualItemPair
QHash< VisualItemPair, FlightPathSegment * > FlightPathSegmentHashTable
QString errorString
Error error
Application Settings.
Definition AppSettings.h:9
Used to convert a Plan to a KML document.
void minAMSLAltitudeChanged(double minAMSLAltitude)
void isROIActiveChanged(void)
void resumeMission(int resumeIndex)
static constexpr int kDefaultsGroupRow
double missionHoverDistance(void) const
double progressPct(void) const
VisualMissionItem * currentPlanViewItem(void) const
bool showPlanFromManagerVehicle(void) final
void visualItemsChanged(void)
SendToVehiclePreCheckState sendToVehiclePreCheck(void)
void currentPlanViewVIIndexChanged(void)
bool dirty(void) const final
static constexpr int kMissionGroupRow
VisualMissionItem * insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int visualItemIndex, bool makeCurrentItem=false)
QmlObjectTreeModel * visualItemsTree(void)
void isInsertTakeoffValidChanged(void)
void batteriesRequiredChanged(int batteriesRequired)
void isInsertLandValidChanged(void)
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
VisualMissionItem * insertTakeoffItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
QGeoCoordinate takeoffCoordinate()
QmlObjectListModel *visualItems READ visualItems NOTIFY visualItemsChanged(QmlObjectTreeModel *visualItemsTree READ visualItemsTree CONSTANT) 1(QPersistentModelIndex planFileGroupIndex READ planFileGroupIndex CONSTANT) 1(QPersistentModelIndex defaultsGroupIndex READ defaultsGroupIndex CONSTANT) 1(QPersistentModelIndex missionGroupIndex READ missionGroupIndex CONSTANT) 1(QPersistentModelIndex fenceGroupIndex READ fenceGroupIndex CONSTANT) 1(QPersistentModelIndex rallyGroupIndex READ rallyGroupIndex CONSTANT) 1(QmlObjectListModel *simpleFlightPathSegments READ simpleFlightPathSegments CONSTANT) 1(QmlObjectListModel *directionArrows READ directionArrows CONSTANT) 1(QStringList complexMissionItemNames READ complexMissionItemNames NOTIFY complexMissionItemNamesChanged) 1(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged) 1(QGeoCoordinate previousCoordinate MEMBER _previousCoordinate NOTIFY previousCoordinateChanged) 1(FlightPathSegment *splitSegment MEMBER _splitSegment NOTIFY splitSegmentChanged) 1(double progressPct READ progressPct NOTIFY progressPctChanged) 1(int missionItemCount READ missionItemCount NOTIFY missionItemCountChanged) 1(int currentMissionIndex READ currentMissionIndex NOTIFY currentMissionIndexChanged) 1(int resumeMissionIndex READ resumeMissionIndex NOTIFY resumeMissionIndexChanged) 1(int currentPlanViewSeqNum READ currentPlanViewSeqNum NOTIFY currentPlanViewSeqNumChanged) 1(int currentPlanViewVIIndex READ currentPlanViewVIIndex NOTIFY currentPlanViewVIIndexChanged) 1(VisualMissionItem *currentPlanViewItem READ currentPlanViewItem NOTIFY currentPlanViewItemChanged) 1(TakeoffMissionItem *takeoffMissionItem READ takeoffMissionItem NOTIFY takeoffMissionItemChanged) 1(double missionTotalDistance READ missionTotalDistance NOTIFY missionTotalDistanceChanged) 1(double missionPlannedDistance READ missionPlannedDistance NOTIFY missionPlannedDistanceChanged) 1(double missionTime READ missionTime NOTIFY missionTimeChanged) 1(double missionHoverDistance READ missionHoverDistance NOTIFY missionHoverDistanceChanged) 1(double missionCruiseDistance READ missionCruiseDistance NOTIFY missionCruiseDistanceChanged) 1(double missionHoverTime READ missionHoverTime NOTIFY missionHoverTimeChanged) 1(double missionCruiseTime READ missionCruiseTime NOTIFY missionCruiseTimeChanged) 1(double missionMaxTelemetry READ missionMaxTelemetry NOTIFY missionMaxTelemetryChanged) 1(int batteryChangePoint READ batteryChangePoint NOTIFY batteryChangePointChanged) 1(int batteriesRequired READ batteriesRequired NOTIFY batteriesRequiredChanged) 1(QGCGeoBoundingCube *travelBoundingCube READ travelBoundingCube NOTIFY missionBoundingCubeChanged) 1(QString surveyComplexItemName READ surveyComplexItemName CONSTANT) 1(QString corridorScanComplexItemName READ corridorScanComplexItemName CONSTANT) 1(QString structureScanComplexItemName READ structureScanComplexItemName CONSTANT) 1(bool onlyInsertTakeoffValid MEMBER _onlyInsertTakeoffValid NOTIFY onlyInsertTakeoffValidChanged) 1(bool isInsertTakeoffValid MEMBER _isInsertTakeoffValid NOTIFY isInsertTakeoffValidChanged) 1(bool isInsertLandValid MEMBER _isInsertLandValid NOTIFY isInsertLandValidChanged) 1(bool hasLandItem MEMBER _hasLandItem NOTIFY hasLandItemChanged) 1(bool multipleLandPatternsAllowed READ multipleLandPatternsAllowed NOTIFY multipleLandPatternsAllowedChanged) 1(bool isROIActive MEMBER _isROIActive NOTIFY isROIActiveChanged) 1(bool isROIBeginCurrentItem MEMBER _isROIBeginCurrentItem NOTIFY isROIBeginCurrentItemChanged) 1(bool flyThroughCommandsAllowed MEMBER _flyThroughCommandsAllowed NOTIFY flyThroughCommandsAllowedChanged) 1(double minAMSLAltitude MEMBER _minAMSLAltitude NOTIFY minAMSLAltitudeChanged) 1(double maxAMSLAltitude MEMBER _maxAMSLAltitude NOTIFY maxAMSLAltitudeChanged) 1(QGroundControlQmlGlobal in visualItemIndexForObject)(QObject *object) const
< Used by Plan view only for interactive editing
VisualMissionItem * insertLandItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
void offsetMission(double eastMeters, double northMeters, double upMeters=0.0, bool offsetTakeoffItems=false, bool offsetLandingItems=false)
void setCurrentPlanViewSeqNum(int sequenceNumber, bool force)
double maxAMSLAltitude(void) const
void maxAMSLAltitudeChanged(double maxAMSLAltitude)
void removeAllFromVehicle(void) final
void recalcTerrainProfile(void)
void missionPlannedDistanceChanged(double missionPlannedDistance)
void missionTotalDistanceChanged(double missionTotalDistance)
QPersistentModelIndex planFileGroupIndex(void) const
void hasLandItemChanged(void)
void _recalcFlightPathSegmentsSignal(void)
void complexMissionItemNamesChanged(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
int missionItemCount(void) const
double missionMaxTelemetry(void) const
void onlyInsertTakeoffValidChanged(void)
void splitSegmentChanged(void)
void repositionMission(const QGeoCoordinate &newHome, bool repositionTakeoffItems=true, bool repositionLandingItems=true)
void resumeMissionReady(void)
@ SendToVehiclePreCheckStateFirwmareVehicleMismatch
void batteryChangePointChanged(int batteryChangePoint)
void globalAltitudeModeChanged(void)
void takeoffMissionItemChanged(void)
void rotateMission(double degreesCW, bool rotateTakeoffItems=false, bool rotateLandingItems=false)
void currentPlanViewSeqNumChanged(void)
static constexpr int kGroupCount
void addMissionToKML(KMLPlanDomDocument &planKML)
void _recalcMissionFlightStatusSignal(void)
void flyThroughCommandsAllowedChanged(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)
QGroundControlQmlGlobal::AltMode globalAltitudeMode(void)
int batteryChangePoint(void) const
-1 for not supported, 0 for not needed
VisualMissionItem * insertROIMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
void plannedHomePositionChanged(QGeoCoordinate plannedHomePosition)
bool isEmpty(void) const
QString surveyComplexItemName(void) const
void newItemsFromVehicle(void)
int currentPlanViewVIIndex(void) const
void save(QJsonObject &json) final
double missionCruiseDistance(void) const
VisualMissionItem * insertSimpleMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem=false)
void missionHoverTimeChanged(void)
bool isFirstLandingComplexItem(const LandingComplexItem *item) const
QGeoCoordinate plannedHomePosition(void) const
QString corridorScanComplexItemName(void) const
QString structureScanComplexItemName(void) const
bool containsItems(void) const final
void progressPctChanged(double progressPct)
void isROIBeginCurrentItemChanged(void)
void missionCruiseTimeChanged(void)
QStringList complexMissionItemNames(void) const
QPersistentModelIndex missionGroupIndex(void) const
QGroundControlQmlGlobal::AltMode globalAltitudeModeDefault(void)
int readyForSaveState(void) const
static constexpr int kPlanFileGroupRow
void currentPlanViewItemChanged(void)
void previousCoordinateChanged(void)
int currentPlanViewSeqNum(void) const
void removeAll(void) final
Removes all from controller only.
void setGlobalAltitudeMode(QGroundControlQmlGlobal::AltMode altMode)
void missionBoundingCubeChanged(void)
bool isInsertTakeoffValid(void) const
double missionCruiseTime(void) const
void missionTimeChanged(void)
QPersistentModelIndex rallyGroupIndex(void) const
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 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
VisualMissionItem * insertCancelROIMissionItem(int visualItemIndex, bool makeCurrentItem=false)
int resumeMissionIndex(void) const
void missionItemCountChanged(int missionItemCount)
VisualMissionItem * insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int visualItemIndex, bool makeCurrentItem=false)
QmlObjectListModel * visualItems(void)
PlanMasterController *masterController READ masterController CONSTANT(bool supported READ supported NOTIFY supportedChanged) 1(bool containsItems READ containsItems NOTIFY containsItemsChanged) 1(bool syncInProgress READ syncInProgress NOTIFY syncInProgressChanged) 1(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) PlanMasterController *masterController(void)
< true: Elemement is non-empty
Master controller for mission, fence, rally.
A SimpleMissionItem is used to represent a single MissionItem to the ui.
double vehicleSpeed
Either cruise or hover speed based on vehicle type and vtol state.
double hoverAmpsTotal
Total hover amps used.
double gimbalPitch
NaN signals pitch was never changed.
QGCMAVLink::VehicleClass_t vtolMode
Either VehicleClassFixedWing, VehicleClassMultiRotor, VehicleClassGeneric (mode unknown)
int batteryChangePoint
-1 for not supported, 0 for not needed
double cruiseAmps
Amp consumption during cruise.
double ampMinutesAvailable
Amp minutes available from single battery.
double cruiseAmpsTotal
Total cruise amps used.
double gimbalYaw
NaN signals yaw was never changed.
double hoverAmps
Amp consumption during hover.