RallyPointManager.h 2.57 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 RallyPointManager_H
#define RallyPointManager_H

#include <QObject>
#include <QGeoCoordinate>

#include "QGCLoggingCategory.h"
17
#include "PlanManager.h"
18 19

class Vehicle;
20
class PlanManager;
21 22 23 24 25 26 27 28 29 30 31 32 33

Q_DECLARE_LOGGING_CATEGORY(RallyPointManagerLog)

/// This is the base class for firmware specific rally point managers. A rally point manager is responsible
/// for communicating with the vehicle to set/get rally points.
class RallyPointManager : public QObject
{
    Q_OBJECT
    
public:
    RallyPointManager(Vehicle* vehicle);
    ~RallyPointManager();
    
34 35 36
    /// Returns true if GeoFence is supported by this vehicle
    virtual bool supported(void) const;

37 38 39 40
    /// Returns true if the manager is currently communicating with the vehicle
    virtual bool inProgress(void) const { return false; }

    /// Load the current settings from the vehicle
DonLakeFlyer's avatar
DonLakeFlyer committed
41
    ///     Signals loadComplete when done
42 43 44
    virtual void loadFromVehicle(void);

    /// Send the current settings to the vehicle
DonLakeFlyer's avatar
DonLakeFlyer committed
45
    ///     Signals sendComplete when done
46 47
    virtual void sendToVehicle(const QList<QGeoCoordinate>& rgPoints);

DonLakeFlyer's avatar
DonLakeFlyer committed
48 49 50
    /// Remove all rally points from the vehicle
    ///     Signals removeAllCompleted when done
    virtual void removeAll(void);
51

52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67
    QList<QGeoCoordinate> points(void) const { return _rgPoints; }

    virtual QString editorQml(void) const { return QStringLiteral("qrc:/FirmwarePlugin/RallyPointEditor.qml"); }

    /// 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 loadComplete       (const QList<QGeoCoordinate> rgPoints);
    void inProgressChanged  (bool inProgress);
    void error              (int errorCode, const QString& errorMsg);
68 69
    void removeAllComplete  (bool error);
    void sendComplete       (bool error);
70

71 72 73
private slots:
    void _planManagerLoadComplete   (bool removeAllRequested);

74 75 76 77
protected:
    void _sendError(ErrorCode_t errorCode, const QString& errorMsg);

    Vehicle*                _vehicle;
78
    PlanManager             _planManager;
79 80 81 82
    QList<QGeoCoordinate>   _rgPoints;
};

#endif