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 <QtCore/QLoggingCategory>
4#include <QtPositioning/QGeoCoordinate>
5#include <QtQmlIntegration/QtQmlIntegration>
6
9#include "Fact.h"
10
11Q_DECLARE_LOGGING_CATEGORY(GeoFenceControllerLog)
12
13class GeoFenceManager;
14class QGCFenceCircle;
15class QGCFencePolygon;
16class Vehicle;
17
19{
20 Q_OBJECT
21 QML_ELEMENT
22 QML_UNCREATABLE("")
23 Q_MOC_INCLUDE("QGCFencePolygon.h")
24 Q_MOC_INCLUDE("QGCFenceCircle.h")
25
26public:
27 GeoFenceController(PlanMasterController* masterController, QObject* parent = nullptr);
29
32 Q_PROPERTY(QGeoCoordinate breachReturnPoint READ breachReturnPoint WRITE setBreachReturnPoint NOTIFY breachReturnPointChanged)
34
35 // Radius of the "paramCircularFence" which is called the "Geofence Failsafe" in PX4 and the "Circular Geofence" on ArduPilot
37
38
41 Q_INVOKABLE void addInclusionPolygon(QGeoCoordinate topLeft, QGeoCoordinate bottomRight);
42
46 Q_INVOKABLE void addInclusionCircle(QGeoCoordinate topLeft, QGeoCoordinate bottomRight);
47
50 Q_INVOKABLE void deletePolygon(int index);
51
54 Q_INVOKABLE void deleteCircle(int index);
55
57 Q_INVOKABLE void clearAllInteractive(void);
58
59 double paramCircularFence (void);
60 Fact* breachReturnAltitude(void) { return &_breachReturnAltitudeFact; }
61
62 // Overrides from PlanElementController
63 bool supported (void) const final;
64 void start (bool flyView) final;
65 void save (QJsonObject& json) final;
66 bool load (const QJsonObject& json, QString& errorString) final;
67 void loadFromVehicle (void) final;
68 void sendToVehicle (void) final;
69 void removeAll (void) final;
70 void removeAllFromVehicle (void) final;
71 bool syncInProgress (void) const final;
72 bool dirty (void) const final;
73 void setDirty (bool dirty) final;
74 bool containsItems (void) const final;
75 bool showPlanFromManagerVehicle (void) final;
76
77 QmlObjectListModel* polygons (void) { return &_polygons; }
78 QmlObjectListModel* circles (void) { return &_circles; }
79 QGeoCoordinate breachReturnPoint (void) const { return _breachReturnPoint; }
80
81 void setBreachReturnPoint (const QGeoCoordinate& breachReturnPoint);
82 bool isEmpty (void) const;
83
84signals:
86 void editorQmlChanged (QString editorQml);
87 void loadComplete (void);
89
90private slots:
91 void _polygonDirtyChanged (bool dirty);
92 void _setDirty (void);
93 void _setFenceFromManager (const QList<QGCFencePolygon>& polygons, const QList<QGCFenceCircle>& circles);
94 void _setReturnPointFromManager (QGeoCoordinate breachReturnPoint);
95 void _managerLoadComplete (void);
96 void _managerSendComplete (bool error);
97 void _managerRemoveAllComplete (bool error);
98 void _parametersReady (void);
99 void _managerVehicleChanged (Vehicle* managerVehicle);
100
101private:
102 void _init(void);
103
104 Vehicle* _managerVehicle = nullptr;
105 GeoFenceManager* _geoFenceManager = nullptr;
106 bool _dirty = false;
107 QmlObjectListModel _polygons;
108 QmlObjectListModel _circles;
109 QGeoCoordinate _breachReturnPoint;
110 Fact _breachReturnAltitudeFact;
111 double _breachReturnDefaultAltitude = qQNaN();
112 bool _itemsRequested = false;
113
114 Fact* _px4ParamCircularFenceFact = nullptr;
115 Fact* _apmParamCircularFenceRadiusFact = nullptr;
116 Fact* _apmParamCircularFenceEnabledFact = nullptr;
117 Fact* _apmParamCircularFenceTypeFact = nullptr;
118
119 static QMap<QString, FactMetaData*> _metaDataMap;
120
121 static constexpr int _jsonCurrentVersion = 2;
122
123 static constexpr const char* _jsonFileTypeValue = "GeoFence";
124 static constexpr const char* _jsonBreachReturnKey = "breachReturn";
125 static constexpr const char* _jsonPolygonsKey = "polygons";
126 static constexpr const char* _jsonCirclesKey = "circles";
127
128 static constexpr const char* _breachReturnAltitudeFactName = "Altitude";
129
130 static constexpr const char* _px4ParamCircularFence = "GF_MAX_HOR_DIST";
131 static constexpr const char* _apmParamCircularFenceRadius = "FENCE_RADIUS";
132 static constexpr const char* _apmParamCircularFenceEnabled = "FENCE_ENABLE";
133 static constexpr const char* _apmParamCircularFenceType = "FENCE_TYPE";
134};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
QString errorString
Error error
A Fact is used to hold a single value within the system.
Definition Fact.h:19
bool showPlanFromManagerVehicle(void) final
Fact * breachReturnAltitude(void)
void removeAllFromVehicle(void) final
QmlObjectListModel *polygons READ polygons QGeoCoordinate bottomRight
void breachReturnPointChanged(QGeoCoordinate breachReturnPoint)
void setDirty(bool dirty) final
bool containsItems(void) const final
double paramCircularFence(void)
QmlObjectListModel * polygons(void)
void sendToVehicle(void) final
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)
void addInclusionCircle(QGeoCoordinate topLeft, QGeoCoordinate bottomRight)
void setBreachReturnPoint(const QGeoCoordinate &breachReturnPoint)
QmlObjectListModel *polygons READ polygons CONSTANT(QmlObjectListModel *circles READ circles CONSTANT) 1(QGeoCoordinate breachReturnPoint READ breachReturnPoint WRITE setBreachReturnPoint NOTIFY breachReturnPointChanged) 1(Fact *breachReturnAltitude READ breachReturnAltitude CONSTANT) 1(double paramCircularFence READ paramCircularFence NOTIFY paramCircularFenceChanged) 1 void addInclusionPolygon(QGeoCoordinate topLeft
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
void clearAllInteractive(void)
Clears the interactive bit from all fence items.
void deleteCircle(int index)
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.