GeoFenceManager.h 3.15 KB
Newer Older
1 2
/****************************************************************************
 *
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8 9
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

10
#pragma once
11 12 13 14

#include <QObject>
#include <QGeoCoordinate>

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

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

class Vehicle;
27
class QmlObjectListModel;
28 29 30

Q_DECLARE_LOGGING_CATEGORY(GeoFenceManagerLog)

31 32
/// 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.
33
class GeoFenceManager : public PlanManager
34 35 36 37 38 39 40
{
    Q_OBJECT
    
public:
    GeoFenceManager(Vehicle* vehicle);
    ~GeoFenceManager();
    
41
    bool supported(void) const;
42

43 44 45 46
    /// Signals sendComplete when done
    void sendToVehicle(const QGeoCoordinate&    breachReturn,   ///< Breach return point
                       QmlObjectListModel&      polygons,       ///< List of QGCFencePolygons
                       QmlObjectListModel&      circles);       ///< List of QGCFenceCircles
47

48 49
    /// Signals removeAllComplete when done
    void removeAll(void);
50

51 52
    /// Returns true if polygon fence is currently enabled on this vehicle
    ///     Signal: polygonEnabledChanged
53
    bool polygonEnabled(void) const { return true; }
54

55 56 57
    const QList<QGCFencePolygon>&   polygons(void) { return _polygons; }
    const QList<QGCFenceCircle>&    circles(void) { return _circles; }
    const QGeoCoordinate&           breachReturnPoint(void) const { return _breachReturnPoint; }
58

59 60 61
    /// Error codes returned in error signal
    typedef enum {
        InternalError,
62 63 64 65 66
        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
67 68 69 70
        InvalidCircleRadius,
    } ErrorCode_t;
    
signals:
71 72 73 74 75
    void loadComplete       (void);
    void inProgressChanged  (bool inProgress);
    void error              (int errorCode, const QString& errorMsg);
    void removeAllComplete  (bool error);
    void sendComplete       (bool error);
76

77 78 79 80 81
private slots:
    void _sendComplete              (bool error);
    void _planManagerLoadComplete   (bool removeAllRequested);

private:
82 83
    void _sendError(ErrorCode_t errorCode, const QString& errorMsg);

84 85
    QList<QGCFencePolygon>  _polygons;
    QList<QGCFenceCircle>   _circles;
86
    QGeoCoordinate          _breachReturnPoint;
87
    bool                    _firstParamLoadComplete = false;
88 89
    QList<QGCFencePolygon>  _sendPolygons;
    QList<QGCFenceCircle>   _sendCircles;
90
#if defined(QGC_AIRMAP_ENABLED)
91
    AirspaceManager*        _airspaceManager        = nullptr;
92
#endif
93
};