3#include <QtCore/QLoggingCategory>
4#include <QtPositioning/QGeoCoordinate>
5#include <QtQmlIntegration/QtQmlIntegration>
23 Q_MOC_INCLUDE(
"QGCFencePolygon.h")
24 Q_MOC_INCLUDE(
"QGCFenceCircle.h")
41 Q_INVOKABLE
void addInclusionPolygon(QGeoCoordinate topLeft, QGeoCoordinate
bottomRight);
64 void start (
bool flyView)
final;
65 void save (QJsonObject& json)
final;
72 bool dirty (
void)
const final;
91 void _polygonDirtyChanged (
bool dirty);
92 void _setDirty (
void);
93 void _setFenceFromManager (
const QList<QGCFencePolygon>&
polygons,
const QList<QGCFenceCircle>&
circles);
95 void _managerLoadComplete (
void);
96 void _managerSendComplete (
bool error);
97 void _managerRemoveAllComplete (
bool error);
98 void _parametersReady (
void);
99 void _managerVehicleChanged (
Vehicle* managerVehicle);
104 Vehicle* _managerVehicle =
nullptr;
109 QGeoCoordinate _breachReturnPoint;
110 Fact _breachReturnAltitudeFact;
111 double _breachReturnDefaultAltitude = qQNaN();
112 bool _itemsRequested =
false;
114 Fact* _px4ParamCircularFenceFact =
nullptr;
115 Fact* _apmParamCircularFenceRadiusFact =
nullptr;
116 Fact* _apmParamCircularFenceEnabledFact =
nullptr;
117 Fact* _apmParamCircularFenceTypeFact =
nullptr;
119 static QMap<QString, FactMetaData*> _metaDataMap;
121 static constexpr int _jsonCurrentVersion = 2;
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";
128 static constexpr const char* _breachReturnAltitudeFactName =
"Altitude";
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";
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
A Fact is used to hold a single value within the system.
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 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
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.