3#include <QtPositioning/QGeoCoordinate>
4#include <QtQmlIntegration/QtQmlIntegration>
20 Q_MOC_INCLUDE(
"QGCFencePolygon.h")
21 Q_MOC_INCLUDE(
"QGCFenceCircle.h")
43 Q_INVOKABLE
void addInclusionCircle(QGeoCoordinate topLeft, QGeoCoordinate bottomRight);
61 void start (
bool flyView)
final;
62 void save (QJsonObject& json)
final;
69 bool dirty (
void)
const final;
88 void _polygonDirtyChanged (
bool dirty);
89 void _setDirty (
void);
90 void _setFenceFromManager (
const QList<QGCFencePolygon>&
polygons,
const QList<QGCFenceCircle>&
circles);
92 void _managerLoadComplete (
void);
93 void _managerSendComplete (
bool error);
94 void _managerRemoveAllComplete (
bool error);
95 void _parametersReady (
void);
96 void _managerVehicleChanged (
Vehicle* managerVehicle);
101 Vehicle* _managerVehicle =
nullptr;
106 QGeoCoordinate _breachReturnPoint;
107 Fact _breachReturnAltitudeFact;
108 double _breachReturnDefaultAltitude = qQNaN();
109 bool _itemsRequested =
false;
111 Fact* _px4ParamCircularFenceFact =
nullptr;
112 Fact* _apmParamCircularFenceRadiusFact =
nullptr;
113 Fact* _apmParamCircularFenceEnabledFact =
nullptr;
114 Fact* _apmParamCircularFenceTypeFact =
nullptr;
116 static QMap<QString, FactMetaData*> _metaDataMap;
118 static constexpr int _jsonCurrentVersion = 2;
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";
125 static constexpr const char* _breachReturnAltitudeFactName =
"Altitude";
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";
A Fact is used to hold a single value within the system.
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 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
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.