Browse Source

List to bracket initializer

QGC4.4
Tomaz Canabrava 6 years ago committed by Daniel Agar
parent
commit
4051b68fd8
  1. 43
      src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc

43
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc

@ -47,28 +47,27 @@ APMCopterMode::APMCopterMode(uint32_t mode, bool settable) :
ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void) ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void)
{ {
QList<APMCustomMode> supportedFlightModes; setSupportedModes({
supportedFlightModes << APMCopterMode(APMCopterMode::STABILIZE ,true); APMCopterMode(APMCopterMode::STABILIZE ,true),
supportedFlightModes << APMCopterMode(APMCopterMode::ACRO ,true); APMCopterMode(APMCopterMode::ACRO ,true),
supportedFlightModes << APMCopterMode(APMCopterMode::ALT_HOLD ,true); APMCopterMode(APMCopterMode::ALT_HOLD ,true),
supportedFlightModes << APMCopterMode(APMCopterMode::AUTO ,true); APMCopterMode(APMCopterMode::AUTO ,true),
supportedFlightModes << APMCopterMode(APMCopterMode::GUIDED ,true); APMCopterMode(APMCopterMode::GUIDED ,true),
supportedFlightModes << APMCopterMode(APMCopterMode::LOITER ,true); APMCopterMode(APMCopterMode::LOITER ,true),
supportedFlightModes << APMCopterMode(APMCopterMode::RTL ,true); APMCopterMode(APMCopterMode::RTL ,true),
supportedFlightModes << APMCopterMode(APMCopterMode::CIRCLE ,true); APMCopterMode(APMCopterMode::CIRCLE ,true),
supportedFlightModes << APMCopterMode(APMCopterMode::LAND ,true); APMCopterMode(APMCopterMode::LAND ,true),
supportedFlightModes << APMCopterMode(APMCopterMode::DRIFT ,true); APMCopterMode(APMCopterMode::DRIFT ,true),
supportedFlightModes << APMCopterMode(APMCopterMode::SPORT ,true); APMCopterMode(APMCopterMode::SPORT ,true),
supportedFlightModes << APMCopterMode(APMCopterMode::FLIP ,true); APMCopterMode(APMCopterMode::FLIP ,true),
supportedFlightModes << APMCopterMode(APMCopterMode::AUTOTUNE ,true); APMCopterMode(APMCopterMode::AUTOTUNE ,true),
supportedFlightModes << APMCopterMode(APMCopterMode::POS_HOLD ,true); APMCopterMode(APMCopterMode::POS_HOLD ,true),
supportedFlightModes << APMCopterMode(APMCopterMode::BRAKE ,true); APMCopterMode(APMCopterMode::BRAKE ,true),
supportedFlightModes << APMCopterMode(APMCopterMode::THROW ,true); APMCopterMode(APMCopterMode::THROW ,true),
supportedFlightModes << APMCopterMode(APMCopterMode::AVOID_ADSB,true); APMCopterMode(APMCopterMode::AVOID_ADSB,true),
supportedFlightModes << APMCopterMode(APMCopterMode::GUIDED_NOGPS,true); APMCopterMode(APMCopterMode::GUIDED_NOGPS,true),
supportedFlightModes << APMCopterMode(APMCopterMode::SAFE_RTL,true); APMCopterMode(APMCopterMode::SAFE_RTL,true),
});
setSupportedModes(supportedFlightModes);
if (!_remapParamNameIntialized) { if (!_remapParamNameIntialized) {
FirmwarePlugin::remapParamNameMap_t& remapV3_6 = _remapParamName[3][6]; FirmwarePlugin::remapParamNameMap_t& remapV3_6 = _remapParamName[3][6];

Loading…
Cancel
Save