APMGeoFenceManager.h 2.41 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
    bool            inProgress          (void) const final;
    void            loadFromVehicle     (void) final;
30
    void            sendToVehicle       (const QGeoCoordinate& breachReturn, QmlObjectListModel& polygon) final;
31 32 33 34 35 36 37
    bool            circleEnabled       (void) const final { return _circleEnabled; }
    bool            polygonEnabled      (void) const final { return _polygonEnabled; }
    bool            breachReturnEnabled (void) const final { return _breachReturnEnabled; }
    float           circleRadius        (void) const final;
    QVariantList    params              (void) const final { return _params; }
    QStringList     paramLabels         (void) const final { return _paramLabels; }
    QString         editorQml           (void) const final;
38
    void            removeAll           (void) final;
39 40 41

private slots:
    void _mavlinkMessageReceived(const mavlink_message_t& message);
42
    void _updateEnabledFlags(void);
43 44 45 46 47 48 49 50 51
    void _circleRadiusRawValueChanged(QVariant value);
    void _parametersReady(void);
    
private:
    void _requestFencePoint(uint8_t pointIndex);
    void _sendFencePoint(uint8_t pointIndex);

private:
    bool _fenceSupported;
52 53 54
    bool _breachReturnEnabled;
    bool _circleEnabled;
    bool _polygonEnabled;
55 56 57 58 59 60 61 62 63 64 65 66 67
    bool _firstParamLoadComplete;

    QVariantList    _params;
    QStringList     _paramLabels;

    bool _readTransactionInProgress;
    bool _writeTransactionInProgress;

    uint8_t _cReadFencePoints;
    uint8_t _cWriteFencePoints;
    uint8_t _currentFencePoint;

    Fact* _fenceTypeFact;
68 69
    Fact* _fenceEnableFact;
    Fact* _circleRadiusFact;
70 71 72 73 74 75 76

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

#endif