GeoFenceManager.h 4.23 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16
/****************************************************************************
 *
 *   (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"
17
#include "FactSystem.h"
18 19

class Vehicle;
20
class QmlObjectListModel;
21 22 23

Q_DECLARE_LOGGING_CATEGORY(GeoFenceManagerLog)

24 25
/// 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.
26 27 28 29 30 31 32 33
class GeoFenceManager : public QObject
{
    Q_OBJECT
    
public:
    GeoFenceManager(Vehicle* vehicle);
    ~GeoFenceManager();
    
34 35 36
    /// Returns true if the manager is currently communicating with the vehicle
    virtual bool inProgress(void) const { return false; }

37
    /// Load the current settings from the vehicle
DonLakeFlyer's avatar
DonLakeFlyer committed
38
    ///     Signals loadComplete when done
39
    virtual void loadFromVehicle(void);
40

41
    /// Send the current settings to the vehicle
DonLakeFlyer's avatar
DonLakeFlyer committed
42
    ///     Signals sendComplete when done
43 44
    virtual void sendToVehicle(const QGeoCoordinate& breachReturn, QmlObjectListModel& polygon);

45
    /// Remove all fence related items from vehicle (does not affect paramters)
DonLakeFlyer's avatar
DonLakeFlyer committed
46 47
    ///     Signals removeAllComplete when done
    virtual void removeAll(void);
48

49 50 51
    /// Returns true if this vehicle support polygon fence
    ///     Signal: polygonSupportedChanged
    virtual bool polygonSupported(void) const { return false; }
52

53 54 55 56 57 58 59 60 61 62 63 64 65 66 67
    /// Returns true if polygon fence is currently enabled on this vehicle
    ///     Signal: polygonEnabledChanged
    virtual bool polygonEnabled(void) const { return false; }

    /// Returns true if breach return is supported by this vehicle
    ///     Signal: breachReturnSupportedChanged
    virtual bool breachReturnSupported(void) const { return false; }

    /// Returns a list of parameter facts that relate to geofence support for the vehicle
    ///     Signal: paramsChanged
    virtual QVariantList params(void) const { return QVariantList(); }

    /// Returns the user visible labels for the paremeters returned by params method
    ///     Signal: paramLabelsChanged
    virtual QStringList paramLabels(void) const { return QStringList(); }
68

69 70 71
    /// Returns true if circular fence is currently enabled on vehicle
    ///     Signal: circleEnabledChanged
    virtual bool circleEnabled(void) const { return false; }
72

73 74 75 76 77 78
    /// Returns the fact which controls the fence circle radius. NULL if not supported
    ///     Signal: circleRadiusFactChanged
    virtual Fact* circleRadiusFact(void) const { return NULL; }

    QList<QGeoCoordinate>   polygon             (void) const { return _polygon; }
    QGeoCoordinate          breachReturnPoint   (void) const { return _breachReturnPoint; }
79

80 81 82 83 84 85 86 87 88
    /// 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:
89 90 91 92 93 94 95 96 97 98
    void loadComplete                   (const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon);
    void inProgressChanged              (bool inProgress);
    void error                          (int errorCode, const QString& errorMsg);
    void paramsChanged                  (QVariantList params);
    void paramLabelsChanged             (QStringList paramLabels);
    void circleEnabledChanged           (bool circleEnabled);
    void circleRadiusFactChanged        (Fact* circleRadiusFact);
    void polygonSupportedChanged        (bool polygonSupported);
    void polygonEnabledChanged          (bool polygonEnabled);
    void breachReturnSupportedChanged   (bool breachReturnSupported);
DonLakeFlyer's avatar
DonLakeFlyer committed
99 100
    void removeAllComplete              (void);
    void sendComplete                   (void);
101

102
protected:
103 104
    void _sendError(ErrorCode_t errorCode, const QString& errorMsg);

105 106 107
    Vehicle*                _vehicle;
    QList<QGeoCoordinate>   _polygon;
    QGeoCoordinate          _breachReturnPoint;
108 109 110
};

#endif