GeoFenceManager.h 2.59 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99
/****************************************************************************
 *
 *   (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 <QTimer>
#include <QGeoCoordinate>

#include "MissionItem.h"
#include "QGCMAVLink.h"
#include "QGCLoggingCategory.h"
#include "LinkInterface.h"
#include "QGCMapPolygon.h"

class Vehicle;

Q_DECLARE_LOGGING_CATEGORY(GeoFenceManagerLog)

class GeoFenceManager : public QObject
{
    Q_OBJECT
    
public:
    GeoFenceManager(Vehicle* vehicle);
    ~GeoFenceManager();
    
    typedef enum {
        GeoFenceNone,
        GeoFenceCircle,
        GeoFencePolygon,
    } GeoFenceType_t;

    typedef struct {
        GeoFenceType_t          fenceType;
        float                   circleRadius;
        QGCMapPolygon           polygon;
        QGeoCoordinate          breachReturnPoint;
    } GeoFence_t;

    bool inProgress(void) const;

    /// Request the geo fence from the vehicle
    void requestGeoFence(void);

    /// Returns the current geofence settings
    const GeoFence_t& geoFence(void) const { return _geoFence; }

    /// Set and send the specified geo fence to the vehicle
    void setGeoFence(const GeoFence_t& geoFence);

    /// Error codes returned in error signal
    typedef enum {
        InternalError,
        TooFewPoints,           ///< Too few points for valid geofence
        TooManyPoints,          ///< Too many points for valid geofence
        InvalidCircleRadius,
    } ErrorCode_t;
    
signals:
    void newGeoFenceAvailable(void);
    void inProgressChanged(bool inProgress);
    void error(int errorCode, const QString& errorMsg);
    
private slots:
    void _mavlinkMessageReceived(const mavlink_message_t& message);
    //void _ackTimeout(void);
    
private:
    void _sendError(ErrorCode_t errorCode, const QString& errorMsg);
    void _clearGeoFence(void);
    void _requestFencePoint(uint8_t pointIndex);
    void _sendFencePoint(uint8_t pointIndex);
    bool _geoFenceSupported(void);

private:
    Vehicle*            _vehicle;
    
    bool        _readTransactionInProgress;
    bool        _writeTransactionInProgress;

    uint8_t     _cReadFencePoints;
    uint8_t     _currentFencePoint;
    QVariant    _savedWriteFenceAction;

    GeoFence_t  _geoFence;

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

#endif