ArduRoverFirmwarePlugin.cc 6.06 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
#include "ArduRoverFirmwarePlugin.h"
11
#include "QGCApplication.h"
12

13 14 15
bool ArduRoverFirmwarePlugin::_remapParamNameIntialized = false;
FirmwarePlugin::remapParamNameMajorVersionMap_t ArduRoverFirmwarePlugin::_remapParamName;

Don Gagne's avatar
Don Gagne committed
16 17
APMRoverMode::APMRoverMode(uint32_t mode, bool settable)
    : APMCustomMode(mode, settable)
18 19 20
{
    QMap<uint32_t,QString> enumToString;
    enumToString.insert(MANUAL,         "Manual");
Don Gagne's avatar
Don Gagne committed
21
    enumToString.insert(ACRO,           "Acro");
22 23
    enumToString.insert(STEERING,       "Steering");
    enumToString.insert(HOLD,           "Hold");
Don Gagne's avatar
Don Gagne committed
24
    enumToString.insert(LOITER,         "Loiter");
Don Gagne's avatar
Don Gagne committed
25
    enumToString.insert(FOLLOW,         "Follow");
Don Gagne's avatar
Don Gagne committed
26
    enumToString.insert(SIMPLE,         "Simple");
27 28
    enumToString.insert(AUTO,           "Auto");
    enumToString.insert(RTL,            "RTL");
Don Gagne's avatar
Don Gagne committed
29
    enumToString.insert(SMART_RTL,      "Smart RTL");
30 31 32 33 34 35
    enumToString.insert(GUIDED,         "Guided");
    enumToString.insert(INITIALIZING,   "Initializing");

    setEnumToStringMapping(enumToString);
}

36
ArduRoverFirmwarePlugin::ArduRoverFirmwarePlugin(void)
37 38 39
{
    QList<APMCustomMode> supportedFlightModes;
    supportedFlightModes << APMRoverMode(APMRoverMode::MANUAL       ,true);
Don Gagne's avatar
Don Gagne committed
40
    supportedFlightModes << APMRoverMode(APMRoverMode::ACRO         ,true);
41 42
    supportedFlightModes << APMRoverMode(APMRoverMode::STEERING     ,true);
    supportedFlightModes << APMRoverMode(APMRoverMode::HOLD         ,true);
Don Gagne's avatar
Don Gagne committed
43
    supportedFlightModes << APMRoverMode(APMRoverMode::LOITER       ,true);
Don Gagne's avatar
Don Gagne committed
44
    supportedFlightModes << APMRoverMode(APMRoverMode::FOLLOW       ,true);
Don Gagne's avatar
Don Gagne committed
45
    supportedFlightModes << APMRoverMode(APMRoverMode::SIMPLE       ,true);
46 47
    supportedFlightModes << APMRoverMode(APMRoverMode::AUTO         ,true);
    supportedFlightModes << APMRoverMode(APMRoverMode::RTL          ,true);
Don Gagne's avatar
Don Gagne committed
48
    supportedFlightModes << APMRoverMode(APMRoverMode::SMART_RTL    ,true);
49 50 51
    supportedFlightModes << APMRoverMode(APMRoverMode::GUIDED       ,true);
    supportedFlightModes << APMRoverMode(APMRoverMode::INITIALIZING ,false);
    setSupportedModes(supportedFlightModes);
52 53 54 55 56 57 58 59 60 61 62 63 64 65 66

    if (!_remapParamNameIntialized) {
        FirmwarePlugin::remapParamNameMap_t& remapV3_2 = _remapParamName[3][2];

        remapV3_2["SERVO5_FUNCTION"] = QStringLiteral("RC5_FUNCTION");
        remapV3_2["SERVO6_FUNCTION"] = QStringLiteral("RC6_FUNCTION");
        remapV3_2["SERVO7_FUNCTION"] = QStringLiteral("RC7_FUNCTION");
        remapV3_2["SERVO8_FUNCTION"] = QStringLiteral("RC8_FUNCTION");
        remapV3_2["SERVO9_FUNCTION"] = QStringLiteral("RC9_FUNCTION");
        remapV3_2["SERVO10_FUNCTION"] = QStringLiteral("RC10_FUNCTION");
        remapV3_2["SERVO11_FUNCTION"] = QStringLiteral("RC11_FUNCTION");
        remapV3_2["SERVO12_FUNCTION"] = QStringLiteral("RC12_FUNCTION");
        remapV3_2["SERVO13_FUNCTION"] = QStringLiteral("RC13_FUNCTION");
        remapV3_2["SERVO14_FUNCTION"] = QStringLiteral("RC14_FUNCTION");

Don Gagne's avatar
Don Gagne committed
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
        remapV3_2["SERVO5_MIN"] = QStringLiteral("RC5_MIN");
        remapV3_2["SERVO6_MIN"] = QStringLiteral("RC6_MIN");
        remapV3_2["SERVO7_MIN"] = QStringLiteral("RC7_MIN");
        remapV3_2["SERVO8_MIN"] = QStringLiteral("RC8_MIN");
        remapV3_2["SERVO9_MIN"] = QStringLiteral("RC9_MIN");
        remapV3_2["SERVO10_MIN"] = QStringLiteral("RC10_MIN");
        remapV3_2["SERVO11_MIN"] = QStringLiteral("RC11_MIN");
        remapV3_2["SERVO12_MIN"] = QStringLiteral("RC12_MIN");
        remapV3_2["SERVO13_MIN"] = QStringLiteral("RC13_MIN");
        remapV3_2["SERVO14_MIN"] = QStringLiteral("RC14_MIN");

        remapV3_2["SERVO5_MAX"] = QStringLiteral("RC5_MAX");
        remapV3_2["SERVO6_MAX"] = QStringLiteral("RC6_MAX");
        remapV3_2["SERVO7_MAX"] = QStringLiteral("RC7_MAX");
        remapV3_2["SERVO8_MAX"] = QStringLiteral("RC8_MAX");
        remapV3_2["SERVO9_MAX"] = QStringLiteral("RC9_MAX");
        remapV3_2["SERVO10_MAX"] = QStringLiteral("RC10_MAX");
        remapV3_2["SERVO11_MAX"] = QStringLiteral("RC11_MAX");
        remapV3_2["SERVO12_MAX"] = QStringLiteral("RC12_MAX");
        remapV3_2["SERVO13_MAX"] = QStringLiteral("RC13_MAX");
        remapV3_2["SERVO14_MAX"] = QStringLiteral("RC14_MAX");

        remapV3_2["SERVO5_REVERSED"] = QStringLiteral("RC5_REVERSED");
        remapV3_2["SERVO6_REVERSED"] = QStringLiteral("RC6_REVERSED");
        remapV3_2["SERVO7_REVERSED"] = QStringLiteral("RC7_REVERSED");
        remapV3_2["SERVO8_REVERSED"] = QStringLiteral("RC8_REVERSED");
        remapV3_2["SERVO9_REVERSED"] = QStringLiteral("RC9_REVERSED");
        remapV3_2["SERVO10_REVERSED"] = QStringLiteral("RC10_REVERSED");
        remapV3_2["SERVO11_REVERSED"] = QStringLiteral("RC11_REVERSED");
        remapV3_2["SERVO12_REVERSED"] = QStringLiteral("RC12_REVERSED");
        remapV3_2["SERVO13_REVERSED"] = QStringLiteral("RC13_REVERSED");
        remapV3_2["SERVO14_REVERSED"] = QStringLiteral("RC14_REVERSED");

100 101 102
        remapV3_2["ARMING_VOLT_MIN"] = QStringLiteral("ARMING_MIN_VOLT");
        remapV3_2["ARMING_VOLT2_MIN"] = QStringLiteral("ARMING_MIN_VOLT2");

103 104 105 106 107
        FirmwarePlugin::remapParamNameMap_t& remapV3_5 = _remapParamName[3][5];

        remapV3_5["BATT_ARM_VOLT"] =    QStringLiteral("ARMING_VOLT_MIN");
        remapV3_5["BATT2_ARM_VOLT"] =   QStringLiteral("ARMING_VOLT2_MIN");

108 109
        _remapParamNameIntialized = true;
    }
110
}
111 112 113

int ArduRoverFirmwarePlugin::remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const
{
114 115
    // Remapping supports up to 3.5
    return majorVersionNumber == 3 ? 5 : Vehicle::versionNotSetValue;
116 117
}

118 119 120 121 122 123 124
void ArduRoverFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange)
{
    Q_UNUSED(vehicle);
    Q_UNUSED(altitudeChange);

    qgcApp()->showMessage(QStringLiteral("Change altitude not supported."));
}
125 126 127 128 129

bool ArduRoverFirmwarePlugin::supportsNegativeThrust(void)
{
    return true;
}