QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
GeoFenceController.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtPositioning/QGeoCoordinate>
4#include <QtQmlIntegration/QtQmlIntegration>
5
8#include "Fact.h"
9
10class GeoFenceManager;
11class QGCFenceCircle;
12class QGCFencePolygon;
13class Vehicle;
14
16{
17 Q_OBJECT
18 QML_ELEMENT
19 QML_UNCREATABLE("")
20 Q_MOC_INCLUDE("QGCFencePolygon.h")
21 Q_MOC_INCLUDE("QGCFenceCircle.h")
22
23public:
24 GeoFenceController(PlanMasterController* masterController, QObject* parent = nullptr);
26
27 Q_PROPERTY(QmlObjectListModel* polygons READ polygons CONSTANT)
28 Q_PROPERTY(QmlObjectListModel* circles READ circles CONSTANT)
29 Q_PROPERTY(QGeoCoordinate breachReturnPoint READ breachReturnPoint WRITE setBreachReturnPoint NOTIFY breachReturnPointChanged)
30 Q_PROPERTY(Fact* breachReturnAltitude READ breachReturnAltitude CONSTANT)
31
32 // Radius of the "paramCircularFence" which is called the "Geofence Failsafe" in PX4 and the "Circular Geofence" on ArduPilot
34
35
38 Q_INVOKABLE void addInclusionPolygon(QGeoCoordinate topLeft, QGeoCoordinate bottomRight);
39
43 Q_INVOKABLE void addInclusionCircle(QGeoCoordinate topLeft, QGeoCoordinate bottomRight);
44
47 Q_INVOKABLE void deletePolygon(int index);
48
51 Q_INVOKABLE void deleteCircle(int index);
52
54 Q_INVOKABLE void clearAllInteractive(void);
55
56 double paramCircularFence (void);
57 Fact* breachReturnAltitude(void) { return &_breachReturnAltitudeFact; }
58
59 // Overrides from PlanElementController
60 bool supported (void) const final;
61 void start (bool flyView) final;
62 void save (QJsonObject& json) final;
63 bool load (const QJsonObject& json, QString& errorString) final;
64 void loadFromVehicle (void) final;
65 void sendToVehicle (void) final;
66 void removeAll (void) final;
67 void removeAllFromVehicle (void) final;
68 bool syncInProgress (void) const final;
69 bool dirty (void) const final;
70 void setDirty (bool dirty) final;
71 bool containsItems (void) const final;
72 bool showPlanFromManagerVehicle (void) final;
73
74 QmlObjectListModel* polygons (void) { return &_polygons; }
75 QmlObjectListModel* circles (void) { return &_circles; }
76 QGeoCoordinate breachReturnPoint (void) const { return _breachReturnPoint; }
77
78 void setBreachReturnPoint (const QGeoCoordinate& breachReturnPoint);
79 bool isEmpty (void) const;
80
81signals:
83 void editorQmlChanged (QString editorQml);
84 void loadComplete (void);
86
87private slots:
88 void _polygonDirtyChanged (bool dirty);
89 void _setDirty (void);
90 void _setFenceFromManager (const QList<QGCFencePolygon>& polygons, const QList<QGCFenceCircle>& circles);
91 void _setReturnPointFromManager (QGeoCoordinate breachReturnPoint);
92 void _managerLoadComplete (void);
93 void _managerSendComplete (bool error);
94 void _managerRemoveAllComplete (bool error);
95 void _parametersReady (void);
96 void _managerVehicleChanged (Vehicle* managerVehicle);
97
98private:
99 void _init(void);
100
101 Vehicle* _managerVehicle = nullptr;
102 GeoFenceManager* _geoFenceManager = nullptr;
103 bool _dirty = false;
104 QmlObjectListModel _polygons;
105 QmlObjectListModel _circles;
106 QGeoCoordinate _breachReturnPoint;
107 Fact _breachReturnAltitudeFact;
108 double _breachReturnDefaultAltitude = qQNaN();
109 bool _itemsRequested = false;
110
111 Fact* _px4ParamCircularFenceFact = nullptr;
112 Fact* _apmParamCircularFenceRadiusFact = nullptr;
113 Fact* _apmParamCircularFenceEnabledFact = nullptr;
114 Fact* _apmParamCircularFenceTypeFact = nullptr;
115
116 static QMap<QString, FactMetaData*> _metaDataMap;
117
118 static constexpr int _jsonCurrentVersion = 2;
119
120 static constexpr const char* _jsonFileTypeValue = "GeoFence";
121 static constexpr const char* _jsonBreachReturnKey = "breachReturn";
122 static constexpr const char* _jsonPolygonsKey = "polygons";
123 static constexpr const char* _jsonCirclesKey = "circles";
124
125 static constexpr const char* _breachReturnAltitudeFactName = "Altitude";
126
127 static constexpr const char* _px4ParamCircularFence = "GF_MAX_HOR_DIST";
128 static constexpr const char* _apmParamCircularFenceRadius = "FENCE_RADIUS";
129 static constexpr const char* _apmParamCircularFenceEnabled = "FENCE_ENABLE";
130 static constexpr const char* _apmParamCircularFenceType = "FENCE_TYPE";
131};
QString errorString
Error error
A Fact is used to hold a single value within the system.
Definition Fact.h:17
bool showPlanFromManagerVehicle(void) final
Fact * breachReturnAltitude(void)
Q_INVOKABLE void addInclusionPolygon(QGeoCoordinate topLeft, QGeoCoordinate bottomRight)
void removeAllFromVehicle(void) final
void breachReturnPointChanged(QGeoCoordinate breachReturnPoint)
void setDirty(bool dirty) final
bool containsItems(void) const final
double paramCircularFence(void)
QmlObjectListModel * polygons(void)
void sendToVehicle(void) final
Q_INVOKABLE void deletePolygon(int index)
QmlObjectListModel * circles(void)
bool syncInProgress(void) const final
void loadComplete(void)
void removeAll(void) final
Removes all from controller only.
void paramCircularFenceChanged(void)
Q_INVOKABLE void addInclusionCircle(QGeoCoordinate topLeft, QGeoCoordinate bottomRight)
void setBreachReturnPoint(const QGeoCoordinate &breachReturnPoint)
bool load(const QJsonObject &json, QString &errorString) final
bool supported(void) const final
true: controller is waiting for the current load to complete
void loadFromVehicle(void) final
bool isEmpty(void) const
void editorQmlChanged(QString editorQml)
bool dirty(void) const final
void start(bool flyView) final
Should be called immediately upon Component.onCompleted.
void save(QJsonObject &json) final
QGeoCoordinate breachReturnPoint(void) const
Q_INVOKABLE void clearAllInteractive(void)
Clears the interactive bit from all fence items.
Q_INVOKABLE void deleteCircle(int index)
This is the base class for firmware specific geofence managers.
This is the abstract base clas for Plan Element controllers.
PlanMasterController * masterController(void)
Master controller for mission, fence, rally.
The QGCFenceCircle class provides a cicle used by GeoFence support.
The QGCFencePolygon class provides a polygon used by GeoFence support.