ArduCopterFirmwarePlugin.h 3.56 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

/// @file
///     @author Don Gagne <don@thegagnes.com>

#ifndef ArduCopterFirmwarePlugin_H
#define ArduCopterFirmwarePlugin_H

#include "APMFirmwarePlugin.h"

19 20 21 22 23 24 25 26 27 28 29 30
class APMCopterMode : public APMCustomMode
{
public:
    enum Mode {
        STABILIZE   = 0,   // hold level position
        ACRO        = 1,   // rate control
        ALT_HOLD    = 2,   // AUTO control
        AUTO        = 3,   // AUTO control
        GUIDED      = 4,   // AUTO control
        LOITER      = 5,   // Hold a single location
        RTL         = 6,   // AUTO control
        CIRCLE      = 7,   // AUTO control
31
        POSITION    = 8,   // Deprecated
32
        LAND        = 9,   // AUTO control
33
        OF_LOITER   = 10,  // Deprecated
34 35
        DRIFT       = 11,  // Drift 'Car Like' mode
        RESERVED_12 = 12,  // RESERVED FOR FUTURE USE
36
        SPORT       = 13,
37 38 39
        FLIP        = 14,
        AUTOTUNE    = 15,
        POS_HOLD    = 16, // HYBRID LOITER.
40 41 42 43
        BRAKE       = 17,
        THROW       = 18,
        AVOID_ADSB  = 19,
        GUIDED_NOGPS= 20,
Don Gagne's avatar
Don Gagne committed
44 45 46 47
        SMART_RTL   = 21,  // SMART_RTL returns to home by retracing its steps
        FLOWHOLD    = 22,  // FLOWHOLD holds position with optical flow without rangefinder
        FOLLOW      = 23,  // follow attempts to follow another vehicle or ground station
        ZIGZAG      = 24,  // ZIGZAG mode is able to fly in a zigzag manner with predefined point A and point B
48 49 50 51 52
    };

    APMCopterMode(uint32_t mode, bool settable);
};

53 54 55
class ArduCopterFirmwarePlugin : public APMFirmwarePlugin
{
    Q_OBJECT
56

57
public:
58
    ArduCopterFirmwarePlugin(void);
Don Gagne's avatar
Don Gagne committed
59 60

    // Overrides from FirmwarePlugin
Don Gagne's avatar
Don Gagne committed
61
    void    guidedModeLand                      (Vehicle* vehicle) final;
62
    const FirmwarePlugin::remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap(void) const final { return _remapParamName; }
Don Gagne's avatar
Don Gagne committed
63 64 65 66
    int     remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const final;
    bool    multiRotorCoaxialMotors             (Vehicle* vehicle) final;
    bool    multiRotorXConfig                   (Vehicle* vehicle) final;
    QString offlineEditingParamFile             (Vehicle* vehicle) final { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Copter.OfflineEditing.params"); }
67 68 69 70
    QString pauseFlightMode                     (void) const override { return QStringLiteral("Brake"); }
    QString landFlightMode                      (void) const override { return QStringLiteral("Land"); }
    QString takeControlFlightMode               (void) const override { return QStringLiteral("Loiter"); }
    QString followFlightMode                    (void) const override { return QStringLiteral("Follow"); }
DonLakeFlyer's avatar
DonLakeFlyer committed
71 72 73
    bool    vehicleYawsToNextWaypointInMission  (const Vehicle* vehicle) const override;
    QString autoDisarmParameter                 (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("DISARM_DELAY"); }
    bool    supportsSmartRTL                    (void) const override { return true; }
74
    void    sendGCSMotionReport                 (Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) override;
75 76 77 78

private:
    static bool _remapParamNameIntialized;
    static FirmwarePlugin::remapParamNameMajorVersionMap_t  _remapParamName;
79 80 81
};

#endif