@ -23,50 +23,56 @@ APMCopterMode::APMCopterMode(uint32_t mode, bool settable) :
@@ -23,50 +23,56 @@ APMCopterMode::APMCopterMode(uint32_t mode, bool settable) :
APMCustomMode ( mode , settable )
{
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 " } ,
{ SAFE_RTL , " Smart RTL " } ,
{ 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 " } ,
{ FOLLOW , " Follow Vehicle " } ,
{ ZIGZAG , " ZigZag " } ,
} ) ;
}
ArduCopterFirmwarePlugin : : ArduCopterFirmwarePlugin ( void )
{
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 : : SAFE_RTL , true ) ,
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 ) ,
APMCopterMode ( APMCopterMode : : FOLLOW , true ) ,
APMCopterMode ( APMCopterMode : : ZIGZAG , true ) ,
} ) ;
if ( ! _remapParamNameIntialized ) {