/**************************************************************************** * * (c) 2009-2016 QGROUNDCONTROL PROJECT * * QGroundControl is licensed according to the terms in the file * COPYING.md in the root of the source code directory. * ****************************************************************************/ #ifndef GeoFenceController_H #define GeoFenceController_H #include "PlanElementController.h" #include "GeoFenceManager.h" #include "QGCMapPolygon.h" #include "Vehicle.h" #include "MultiVehicleManager.h" #include "QGCLoggingCategory.h" Q_DECLARE_LOGGING_CATEGORY(GeoFenceControllerLog) class GeoFenceController : public PlanElementController { Q_OBJECT public: GeoFenceController(QObject* parent = NULL); ~GeoFenceController(); Q_PROPERTY(bool fenceSupported READ fenceSupported NOTIFY fenceSupportedChanged) Q_PROPERTY(bool circleSupported READ circleSupported NOTIFY circleSupportedChanged) Q_PROPERTY(bool polygonSupported READ polygonSupported NOTIFY polygonSupportedChanged) Q_PROPERTY(bool breachReturnSupported READ breachReturnSupported NOTIFY breachReturnSupportedChanged) Q_PROPERTY(float circleRadius READ circleRadius NOTIFY circleRadiusChanged) Q_PROPERTY(QGCMapPolygon* polygon READ polygon CONSTANT) Q_PROPERTY(QGeoCoordinate breachReturnPoint READ breachReturnPoint WRITE setBreachReturnPoint NOTIFY breachReturnPointChanged) Q_PROPERTY(QVariantList params READ params NOTIFY paramsChanged) Q_PROPERTY(QStringList paramLabels READ paramLabels NOTIFY paramLabelsChanged) void start (bool editMode) final; void loadFromVehicle (void) final; void sendToVehicle (void) final; void loadFromFilePicker (void) final; void loadFromFile (const QString& filename) final; void saveToFilePicker (void) final; void saveToFile (const QString& filename) final; void removeAll (void) final; bool syncInProgress (void) const final; bool dirty (void) const final; void setDirty (bool dirty) final; bool fenceSupported (void) const; bool circleSupported (void) const; bool polygonSupported (void) const; bool breachReturnSupported (void) const; float circleRadius (void) const; QGCMapPolygon* polygon (void) { return &_polygon; } QGeoCoordinate breachReturnPoint (void) const { return _breachReturnPoint; } QVariantList params (void) const; QStringList paramLabels (void) const; public slots: void setBreachReturnPoint(const QGeoCoordinate& breachReturnPoint); signals: void fenceSupportedChanged (bool fenceSupported); void circleSupportedChanged (bool circleSupported); void polygonSupportedChanged (bool polygonSupported); void breachReturnSupportedChanged (bool breachReturnSupported); void circleRadiusChanged (float circleRadius); void polygonPathChanged (const QVariantList& polygonPath); void breachReturnPointChanged (QGeoCoordinate breachReturnPoint); void paramsChanged (QVariantList params); void paramLabelsChanged (QStringList paramLabels); private slots: void _polygonDirtyChanged(bool dirty); void _setDirty(void); void _setPolygon(const QList& polygon); private: void _clearGeoFence(void); void _signalAll(void); void _activeVehicleBeingRemoved(Vehicle* vehicle) final; void _activeVehicleSet(void) final; bool _dirty; QGCMapPolygon _polygon; QGeoCoordinate _breachReturnPoint; QVariantList _params; }; #endif