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

class Vehicle;

Q_DECLARE_LOGGING_CATEGORY(GeoFenceManagerLog)

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

35
    /// Load the current settings from the vehicle
36
    virtual void loadFromVehicle(void);
37

38
    /// Send the current settings to the vehicle
39
    virtual void sendToVehicle(const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon);
40

41 42 43
    virtual bool circleEnabled          (void) const { return false; }
    virtual bool polygonEnabled         (void) const { return false; }
    virtual bool breachReturnEnabled    (void) const { return false; }
44

45 46 47
    virtual float           circleRadius        (void) const { return 0.0; }
    QList<QGeoCoordinate>   polygon             (void) const { return _polygon; }
    QGeoCoordinate          breachReturnPoint   (void) const { return _breachReturnPoint; }
48

49 50
    virtual QVariantList    params      (void) const { return QVariantList(); }
    virtual QStringList     paramLabels (void) const { return QStringList(); }
51

52
    virtual QString editorQml(void) const { return QStringLiteral("qrc:/FirmwarePlugin/NoGeoFenceEditor.qml"); }
53

54 55 56 57 58 59 60 61 62
    /// 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:
63 64 65 66 67 68 69 70 71
    void loadComplete               (const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon);
    void circleEnabledChanged       (bool circleEnabled);
    void polygonEnabledChanged      (bool polygonEnabled);
    void breachReturnEnabledChanged (bool fenceEnabled);
    void circleRadiusChanged        (float circleRadius);
    void inProgressChanged          (bool inProgress);
    void error                      (int errorCode, const QString& errorMsg);
    void paramsChanged              (QVariantList params);
    void paramLabelsChanged         (QStringList paramLabels);
72
    
73
protected:
74 75
    void _sendError(ErrorCode_t errorCode, const QString& errorMsg);

76 77 78
    Vehicle*                _vehicle;
    QList<QGeoCoordinate>   _polygon;
    QGeoCoordinate          _breachReturnPoint;
79 80 81
};

#endif