ArduRoverFirmwarePlugin.cc 2.94 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
#include "ArduRoverFirmwarePlugin.h"

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

Don Gagne's avatar
Don Gagne committed
15 16
APMRoverMode::APMRoverMode(uint32_t mode, bool settable)
    : APMCustomMode(mode, settable)
17 18 19 20 21 22 23 24 25 26 27 28 29 30
{
    QMap<uint32_t,QString> enumToString;
    enumToString.insert(MANUAL,         "Manual");
    enumToString.insert(LEARNING,       "Learning");
    enumToString.insert(STEERING,       "Steering");
    enumToString.insert(HOLD,           "Hold");
    enumToString.insert(AUTO,           "Auto");
    enumToString.insert(RTL,            "RTL");
    enumToString.insert(GUIDED,         "Guided");
    enumToString.insert(INITIALIZING,   "Initializing");

    setEnumToStringMapping(enumToString);
}

31
ArduRoverFirmwarePlugin::ArduRoverFirmwarePlugin(void)
32 33 34 35 36 37 38 39 40 41 42
{
    QList<APMCustomMode> supportedFlightModes;
    supportedFlightModes << APMRoverMode(APMRoverMode::MANUAL       ,true);
    supportedFlightModes << APMRoverMode(APMRoverMode::LEARNING     ,true);
    supportedFlightModes << APMRoverMode(APMRoverMode::STEERING     ,true);
    supportedFlightModes << APMRoverMode(APMRoverMode::HOLD         ,true);
    supportedFlightModes << APMRoverMode(APMRoverMode::AUTO         ,true);
    supportedFlightModes << APMRoverMode(APMRoverMode::RTL          ,true);
    supportedFlightModes << APMRoverMode(APMRoverMode::GUIDED       ,true);
    supportedFlightModes << APMRoverMode(APMRoverMode::INITIALIZING ,false);
    setSupportedModes(supportedFlightModes);
43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59

    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");

        _remapParamNameIntialized = true;
    }
60
}
61 62 63 64 65 66 67

int ArduRoverFirmwarePlugin::remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const
{
    // Remapping supports up to 3.2
    return majorVersionNumber == 3 ? 2 : Vehicle::versionNotSetValue;
}