GeoFenceManager.h 3.8 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15
/****************************************************************************
 *
 *   (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>

16
#if defined(QGC_AIRMAP_ENABLED)
Gus Grubba's avatar
Gus Grubba committed
17
#include "AirspaceManager.h"
18 19
#endif

20
#include "QGCLoggingCategory.h"
21
#include "FactSystem.h"
22 23 24
#include "PlanManager.h"
#include "QGCFencePolygon.h"
#include "QGCFenceCircle.h"
25 26

class Vehicle;
27
class QmlObjectListModel;
28
class PlanManager;
29 30 31

Q_DECLARE_LOGGING_CATEGORY(GeoFenceManagerLog)

32 33
/// 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.
34 35 36 37 38 39 40 41
class GeoFenceManager : public QObject
{
    Q_OBJECT
    
public:
    GeoFenceManager(Vehicle* vehicle);
    ~GeoFenceManager();
    
42 43 44
    /// Returns true if GeoFence is supported by this vehicle
    virtual bool supported(void) const;

45
    /// Returns true if the manager is currently communicating with the vehicle
46
    virtual bool inProgress(void) const;
47

48
    /// Load the current settings from the vehicle
DonLakeFlyer's avatar
DonLakeFlyer committed
49
    ///     Signals loadComplete when done
50
    virtual void loadFromVehicle(void);
51

52
    /// Send the geofence settings to the vehicle
DonLakeFlyer's avatar
DonLakeFlyer committed
53
    ///     Signals sendComplete when done
54 55 56
    virtual void sendToVehicle(const QGeoCoordinate&    breachReturn,   ///< Breach return point
                               QmlObjectListModel&      polygons,       ///< List of QGCFencePolygons
                               QmlObjectListModel&      circles);       ///< List of QGCFenceCircles
57

Patrick José Pereira's avatar
Patrick José Pereira committed
58
    /// Remove all fence related items from vehicle (does not affect parameters)
DonLakeFlyer's avatar
DonLakeFlyer committed
59 60
    ///     Signals removeAllComplete when done
    virtual void removeAll(void);
61

62 63
    /// Returns true if polygon fence is currently enabled on this vehicle
    ///     Signal: polygonEnabledChanged
64
    virtual bool polygonEnabled(void) const { return true; }
65

66 67 68
    const QList<QGCFencePolygon>&   polygons(void) { return _polygons; }
    const QList<QGCFenceCircle>&    circles(void) { return _circles; }
    const QGeoCoordinate&           breachReturnPoint(void) const { return _breachReturnPoint; }
69

70 71 72
    /// Error codes returned in error signal
    typedef enum {
        InternalError,
73 74 75 76 77
        PolygonTooFewPoints,    ///< Too few points for valid fence polygon
        PolygonTooManyPoints,   ///< Too many points for valid fence polygon
        IncompletePolygonLoad,  ///< Incomplete polygon loaded
        UnsupportedCommand,     ///< Usupported command in mission type
        BadPolygonItemFormat,   ///< Error re-creating polygons from mission items
78 79 80 81
        InvalidCircleRadius,
    } ErrorCode_t;
    
signals:
82
    void loadComplete                   (void);
83 84
    void inProgressChanged              (bool inProgress);
    void error                          (int errorCode, const QString& errorMsg);
85 86
    void removeAllComplete              (bool error);
    void sendComplete                   (bool error);
87

88 89 90 91 92
private slots:
    void _sendComplete              (bool error);
    void _planManagerLoadComplete   (bool removeAllRequested);

private:
93 94
    void _sendError(ErrorCode_t errorCode, const QString& errorMsg);

95
    Vehicle*                _vehicle;
96 97 98
    PlanManager             _planManager;
    QList<QGCFencePolygon>  _polygons;
    QList<QGCFenceCircle>   _circles;
99
    QGeoCoordinate          _breachReturnPoint;
100 101 102
    bool                    _firstParamLoadComplete;
    QList<QGCFencePolygon>  _sendPolygons;
    QList<QGCFenceCircle>   _sendCircles;
103
#if defined(QGC_AIRMAP_ENABLED)
104
    AirspaceManager*         _airspaceManager;
105
#endif
106 107 108
};

#endif