ArduRoverFirmwarePlugin.h 1.78 KB
Newer Older
1 2 3 4 5 6 7 8 9
/****************************************************************************
 *
 *   (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.
 *
 ****************************************************************************/

10 11 12 13 14 15 16 17 18 19 20 21 22

/// @file
///     @author Pritam Ghanghas <pritam.ghanghas@gmail.com>

#ifndef ArduRoverFirmwarePlugin_H
#define ArduRoverFirmwarePlugin_H

#include "APMFirmwarePlugin.h"

class APMRoverMode : public APMCustomMode
{
public:
    enum Mode {
Don Gagne's avatar
Don Gagne committed
23 24 25 26 27
        MANUAL          = 0,
        ACRO            = 1,
        STEERING        = 3,
        HOLD            = 4,
        LOITER          = 5,
Don Gagne's avatar
Don Gagne committed
28
        FOLLOW          = 6,
Don Gagne's avatar
Don Gagne committed
29 30 31 32 33 34
        SIMPLE          = 7,
        AUTO            = 10,
        RTL             = 11,
        SMART_RTL       = 12,
        GUIDED          = 15,
        INITIALIZING    = 16,
35 36 37 38 39 40 41 42 43 44 45
    };
    static const int modeCount = 17;

    APMRoverMode(uint32_t mode, bool settable);
};

class ArduRoverFirmwarePlugin : public APMFirmwarePlugin
{
    Q_OBJECT
    
public:
46
    ArduRoverFirmwarePlugin(void);
47 48

    // Overrides from FirmwarePlugin
49 50 51
    QString pauseFlightMode                         (void) const override { return QString("Hold"); }
    void    guidedModeChangeAltitude                (Vehicle* vehicle, double altitudeChange) final;
    int     remapParamNameHigestMinorVersionNumber  (int majorVersionNumber) const final;
52
    const FirmwarePlugin::remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap(void) const final { return _remapParamName; }
53
    bool supportsNegativeThrust(void) final;
54 55 56 57

private:
    static bool _remapParamNameIntialized;
    static FirmwarePlugin::remapParamNameMajorVersionMap_t  _remapParamName;
58 59 60
};

#endif