5bool ArduCopterFirmwarePlugin::_remapParamNameIntialized =
false;
71 if (!_remapParamNameIntialized) {
74 remapV4_0[
"TUNE_MIN"] = QStringLiteral(
"TUNE_LOW");
75 remapV4_0[
"TUNE_MAX"] = QStringLiteral(
"TUNE_HIGH");
77 _remapParamNameIntialized =
true;
124 mode.fixedWing =
false;
125 mode.multiRotor =
true;
QList< FirmwareFlightMode > FlightModeList
This is the base class for all stack specific APM firmware plugins.
ArduCopterFirmwarePlugin(QObject *parent=nullptr)
uint32_t _convertToCustomFlightModeEnum(uint32_t val) const override
void updateAvailableFlightModes(FlightModeList &modeList) override
Update Available flight modes recieved from vehicle.
QString followFlightMode() const override
Returns the flight mode which the vehicle will be for follow me.
int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const override
Returns the highest major version number that is known to the remap for this specified major version.
QString landFlightMode() const override
Returns the flight mode for Land.
QString stabilizedFlightMode() const override
Returns the flight mode for Stabilized.
bool multiRotorXConfig(Vehicle *vehicle) const override
QString pauseFlightMode() const override
Returns The flight mode which indicates the vehicle is paused.
~ArduCopterFirmwarePlugin()
QString takeControlFlightMode() const override
Returns the flight mode to use when the operator wants to take back control from autonomouse flight.
void _setModeEnumToModeStringMapping(FlightModeCustomModeMap enumToString)
void _updateFlightModeList(FlightModeList &flightModeList)
QMap< QString, QString > remapParamNameMap_t
FlightModeCustomModeMap _modeEnumToString
QMap< int, remapParamNameMinorVersionRemapMap_t > remapParamNameMajorVersionMap_t
Fact * getParameter(int componentId, const QString ¶mName)
static constexpr int defaultComponentId
static const int versionNotSetValue
ParameterManager * parameterManager()