ArduCopterFirmwarePlugin.cc 5.44 KB
Newer Older
1 2
/****************************************************************************
 *
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8 9
 *
 * 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

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

#include "ArduCopterFirmwarePlugin.h"
Don Gagne's avatar
Don Gagne committed
15 16
#include "QGCApplication.h"
#include "MissionManager.h"
17
#include "ParameterManager.h"
18

19 20 21
bool ArduCopterFirmwarePlugin::_remapParamNameIntialized = false;
FirmwarePlugin::remapParamNameMajorVersionMap_t ArduCopterFirmwarePlugin::_remapParamName;

Don Gagne's avatar
Don Gagne committed
22 23
APMCopterMode::APMCopterMode(uint32_t mode, bool settable) :
    APMCustomMode(mode, settable)
24
{
25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51
    setEnumToStringMapping({
        { STABILIZE,    "Stabilize"},
        { ACRO,         "Acro"},
        { ALT_HOLD,     "Altitude Hold"},
        { AUTO,         "Auto"},
        { GUIDED,       "Guided"},
        { LOITER,       "Loiter"},
        { RTL,          "RTL"},
        { CIRCLE,       "Circle"},
        { LAND,         "Land"},
        { DRIFT,        "Drift"},
        { SPORT,        "Sport"},
        { FLIP,         "Flip"},
        { AUTOTUNE,     "Autotune"},
        { POS_HOLD,     "Position Hold"},
        { BRAKE,        "Brake"},
        { THROW,        "Throw"},
        { AVOID_ADSB,   "Avoid ADSB"},
        { GUIDED_NOGPS, "Guided No GPS"},
        { SMART_RTL,    "Smart RTL"},
        { FLOWHOLD,     "Flow Hold" },
#if 0
    // Follow me not ready for Stable
        { FOLLOW,       "Follow" },
#endif
        { ZIGZAG,       "ZigZag" },
    });
52 53
}

54
ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void)
55
{
56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82
    setSupportedModes({
        APMCopterMode(APMCopterMode::STABILIZE,     true),
        APMCopterMode(APMCopterMode::ACRO,          true),
        APMCopterMode(APMCopterMode::ALT_HOLD,      true),
        APMCopterMode(APMCopterMode::AUTO,          true),
        APMCopterMode(APMCopterMode::GUIDED,        true),
        APMCopterMode(APMCopterMode::LOITER,        true),
        APMCopterMode(APMCopterMode::RTL,           true),
        APMCopterMode(APMCopterMode::CIRCLE,        true),
        APMCopterMode(APMCopterMode::LAND,          true),
        APMCopterMode(APMCopterMode::DRIFT,         true),
        APMCopterMode(APMCopterMode::SPORT,         true),
        APMCopterMode(APMCopterMode::FLIP,          true),
        APMCopterMode(APMCopterMode::AUTOTUNE,      true),
        APMCopterMode(APMCopterMode::POS_HOLD,      true),
        APMCopterMode(APMCopterMode::BRAKE,         true),
        APMCopterMode(APMCopterMode::THROW,         true),
        APMCopterMode(APMCopterMode::AVOID_ADSB,    true),
        APMCopterMode(APMCopterMode::GUIDED_NOGPS,  true),
        APMCopterMode(APMCopterMode::SMART_RTL,     true),
        APMCopterMode(APMCopterMode::FLOWHOLD,      true),
#if 0
    // Follow me not ready for Stable
        APMCopterMode(APMCopterMode::FOLLOW,        true),
#endif
        APMCopterMode(APMCopterMode::ZIGZAG,        true),
    });
83 84

    if (!_remapParamNameIntialized) {
85 86
        FirmwarePlugin::remapParamNameMap_t& remapV3_6 = _remapParamName[3][6];

87
        remapV3_6["BATT_AMP_PERVLT"] =  QStringLiteral("BATT_AMP_PERVOL");
88
        remapV3_6["BATT2_AMP_PERVLT"] = QStringLiteral("BATT2_AMP_PERVOL");
89 90 91 92 93
        remapV3_6["BATT_LOW_MAH"] =     QStringLiteral("FS_BATT_MAH");
        remapV3_6["BATT_LOW_VOLT"] =    QStringLiteral("FS_BATT_VOLTAGE");
        remapV3_6["BATT_FS_LOW_ACT"] =  QStringLiteral("FS_BATT_ENABLE");
        remapV3_6["PSC_ACCZ_P"] =       QStringLiteral("ACCEL_Z_P");
        remapV3_6["PSC_ACCZ_I"] =       QStringLiteral("ACCEL_Z_I");
94

95 96 97 98
        FirmwarePlugin::remapParamNameMap_t& remapV3_7 = _remapParamName[3][7];

        remapV3_7["BATT_ARM_VOLT"] =    QStringLiteral("ARMING_VOLT_MIN");
        remapV3_7["BATT2_ARM_VOLT"] =   QStringLiteral("ARMING_VOLT2_MIN");
99 100 101 102 103 104 105 106 107 108 109
        remapV3_7["RC7_OPTION"] =       QStringLiteral("CH7_OPT");
        remapV3_7["RC8_OPTION"] =       QStringLiteral("CH8_OPT");
        remapV3_7["RC9_OPTION"] =       QStringLiteral("CH9_OPT");
        remapV3_7["RC10_OPTION"] =      QStringLiteral("CH10_OPT");
        remapV3_7["RC11_OPTION"] =      QStringLiteral("CH11_OPT");
        remapV3_7["RC12_OPTION"] =      QStringLiteral("CH12_OPT");

        FirmwarePlugin::remapParamNameMap_t& remapV4_0 = _remapParamName[4][0];

        remapV4_0["TUNE_MIN"] = QStringLiteral("TUNE_HIGH");
        remapV3_7["TUNE_MAX"] = QStringLiteral("TUNE_LOW");
110

111
        _remapParamNameIntialized = true;
112 113 114 115 116
    }
}

int ArduCopterFirmwarePlugin::remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const
{
117 118
    // Remapping supports up to 3.7
    return majorVersionNumber == 3 ? 7 : Vehicle::versionNotSetValue;
119
}
Don Gagne's avatar
Don Gagne committed
120 121 122

void ArduCopterFirmwarePlugin::guidedModeLand(Vehicle* vehicle)
{
123
    _setFlightModeAndValidate(vehicle, "Land");
Don Gagne's avatar
Don Gagne committed
124 125
}

Don Gagne's avatar
Don Gagne committed
126 127 128 129 130 131 132 133
bool ArduCopterFirmwarePlugin::multiRotorCoaxialMotors(Vehicle* vehicle)
{
    Q_UNUSED(vehicle);
    return _coaxialMotors;
}

bool ArduCopterFirmwarePlugin::multiRotorXConfig(Vehicle* vehicle)
{
134
    return vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "FRAME")->rawValue().toInt() != 0;
Don Gagne's avatar
Don Gagne committed
135
}
136

137 138 139
#if 0
    // Follow me not ready for Stable
void ArduCopterFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities)
140
{
141
    _sendGCSMotionReport(vehicle, motionReport, estimatationCapabilities);
142
}
143
#endif