GeoFenceManager.h 3.71 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
#include "AirMapManager.h"
17
#include "QGCLoggingCategory.h"
18
#include "FactSystem.h"
19 20 21
#include "PlanManager.h"
#include "QGCFencePolygon.h"
#include "QGCFenceCircle.h"
22 23

class Vehicle;
24
class QmlObjectListModel;
25
class PlanManager;
26 27 28

Q_DECLARE_LOGGING_CATEGORY(GeoFenceManagerLog)

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

42
    /// Returns true if the manager is currently communicating with the vehicle
43
    virtual bool inProgress(void) const;
44

45
    /// Load the current settings from the vehicle
DonLakeFlyer's avatar
DonLakeFlyer committed
46
    ///     Signals loadComplete when done
47
    virtual void loadFromVehicle(void);
48

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

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

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

63 64 65
    const QList<QGCFencePolygon>&   polygons(void) { return _polygons; }
    const QList<QGCFenceCircle>&    circles(void) { return _circles; }
    const QGeoCoordinate&           breachReturnPoint(void) const { return _breachReturnPoint; }
66

67 68 69
    /// Error codes returned in error signal
    typedef enum {
        InternalError,
70 71 72 73 74
        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
75 76 77 78
        InvalidCircleRadius,
    } ErrorCode_t;
    
signals:
79
    void loadComplete                   (void);
80 81
    void inProgressChanged              (bool inProgress);
    void error                          (int errorCode, const QString& errorMsg);
82 83
    void removeAllComplete              (bool error);
    void sendComplete                   (bool error);
84

85 86 87 88 89
private slots:
    void _sendComplete              (bool error);
    void _planManagerLoadComplete   (bool removeAllRequested);

private:
90 91
    void _sendError(ErrorCode_t errorCode, const QString& errorMsg);

92
    Vehicle*                _vehicle;
93 94 95
    PlanManager             _planManager;
    QList<QGCFencePolygon>  _polygons;
    QList<QGCFenceCircle>   _circles;
96
    QGeoCoordinate          _breachReturnPoint;
97 98 99
    bool                    _firstParamLoadComplete;
    QList<QGCFencePolygon>  _sendPolygons;
    QList<QGCFenceCircle>   _sendCircles;
100
    AirMapManager*         _airmapManager;
101 102 103
};

#endif