APMGeoFenceManager.h 2.59 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 APMGeoFenceManager_H
#define APMGeoFenceManager_H

#include "GeoFenceManager.h"
#include "QGCMAVLink.h"
#include "FactSystem.h"

17 18
class QmlObjectListModel;

19 20 21 22 23 24 25 26 27
class APMGeoFenceManager : public GeoFenceManager
{
    Q_OBJECT
    
public:
    APMGeoFenceManager(Vehicle* vehicle);
    ~APMGeoFenceManager();

    // Overrides from GeoFenceManager
28 29 30 31 32 33 34 35 36 37 38
    bool            inProgress              (void) const final;
    void            loadFromVehicle         (void) final;
    void            sendToVehicle           (const QGeoCoordinate& breachReturn, QmlObjectListModel& polygon) final;
    bool            polygonSupported        (void) const final { return _polygonSupported; }
    bool            polygonEnabled          (void) const final { return _polygonEnabled; }
    bool            breachReturnSupported   (void) const final { return _breachReturnSupported; }
    bool            circleEnabled           (void) const { return _circleEnabled; }
    Fact*           circleRadiusFact        (void) const { return _circleRadiusFact; }
    QVariantList    params                  (void) const final { return _params; }
    QStringList     paramLabels             (void) const final { return _paramLabels; }
    void            removeAll               (void) final;
39 40

private slots:
41 42
    void _mavlinkMessageReceived    (const mavlink_message_t& message);
    void _parametersReady           (void);
43 44
    
private:
45 46 47 48 49
    void _requestFencePoint (uint8_t pointIndex);
    void _sendFencePoint    (uint8_t pointIndex);
    void _updateEnabledFlags(void);
    void _setCircleEnabled  (bool circleEnabled);
    void _setPolygonEnabled (bool polygonEnabled);
50 51 52

private:
    bool _fenceSupported;
53
    bool _circleEnabled;
54
    bool _polygonSupported;
55
    bool _polygonEnabled;
56
    bool _breachReturnSupported;
57 58 59 60 61 62 63 64 65 66 67 68 69
    bool _firstParamLoadComplete;

    QVariantList    _params;
    QStringList     _paramLabels;

    bool _readTransactionInProgress;
    bool _writeTransactionInProgress;

    uint8_t _cReadFencePoints;
    uint8_t _cWriteFencePoints;
    uint8_t _currentFencePoint;

    Fact* _fenceTypeFact;
70 71
    Fact* _fenceEnableFact;
    Fact* _circleRadiusFact;
72 73 74 75 76 77 78

    static const char* _fenceTotalParam;
    static const char* _fenceActionParam;
    static const char* _fenceEnableParam;
};

#endif