GeoFenceManager.h 3.33 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

#ifndef GeoFenceManager_H
#define GeoFenceManager_H

#include <QObject>
#include <QGeoCoordinate>

#include "QGCLoggingCategory.h"
#include "QGCMapPolygon.h"

class Vehicle;

Q_DECLARE_LOGGING_CATEGORY(GeoFenceManagerLog)

23 24
/// This is the base class for firmware specific geofence managers. A geofence manager is responsible
/// for communicating with the vehicle to set/get geofence settings.
25 26 27 28 29 30 31 32
class GeoFenceManager : public QObject
{
    Q_OBJECT
    
public:
    GeoFenceManager(Vehicle* vehicle);
    ~GeoFenceManager();
    
33 34 35 36 37
    /// Returns true if the manager is currently communicating with the vehicle
    virtual bool inProgress(void) const { return false; }

    /// Load the current settings from teh vehicle
    virtual void loadFromVehicle(void);
38

39 40
    /// Send the current settings to the vehicle
    virtual void sendToVehicle(void);
41

42 43 44 45 46
    // Support flags
    virtual bool fenceSupported         (void) const { return false; }
    virtual bool circleSupported        (void) const { return false; }
    virtual bool polygonSupported       (void) const { return false; }
    virtual bool breachReturnSupported  (void) const { return false; }
47

48 49 50
    virtual float           circleRadius        (void) const { return 0.0; }
    QList<QGeoCoordinate>   polygon             (void) const { return _polygon; }
    QGeoCoordinate          breachReturnPoint   (void) const { return _breachReturnPoint; }
51

52 53
    virtual QVariantList    params      (void) const { return QVariantList(); }
    virtual QStringList     paramLabels (void) const { return QStringList(); }
54

55 56
    virtual QString editorQml(void) const { return QStringLiteral("qrc:/FirmwarePlugin/GeoFenceEditor.qml"); }

57 58
    void setPolygon(QGCMapPolygon* polygon);
    void setBreachReturnPoint(const QGeoCoordinate& breachReturnPoint);
59 60 61 62 63 64 65 66 67 68

    /// Error codes returned in error signal
    typedef enum {
        InternalError,
        TooFewPoints,           ///< Too few points for valid geofence
        TooManyPoints,          ///< Too many points for valid geofence
        InvalidCircleRadius,
    } ErrorCode_t;
    
signals:
69 70 71 72 73 74 75 76 77 78 79
    void fenceSupportedChanged          (bool fenceSupported);
    void circleSupportedChanged         (bool circleSupported);
    void polygonSupportedChanged        (bool polygonSupported);
    void breachReturnSupportedChanged   (bool fenceSupported);
    void circleRadiusChanged            (float circleRadius);
    void polygonChanged                 (QList<QGeoCoordinate> polygon);
    void breachReturnPointChanged       (QGeoCoordinate breachReturnPoint);
    void inProgressChanged              (bool inProgress);
    void error                          (int errorCode, const QString& errorMsg);
    void paramsChanged                  (QVariantList params);
    void paramLabelsChanged             (QStringList paramLabels);
80
    
81
protected:
82 83
    void _sendError(ErrorCode_t errorCode, const QString& errorMsg);

84 85 86
    Vehicle*                _vehicle;
    QList<QGeoCoordinate>   _polygon;
    QGeoCoordinate          _breachReturnPoint;
87 88 89
};

#endif