diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 700babe8a0..ae85157f2d 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -258,42 +258,42 @@ const AP_Param::Info Copter::var_info[] = { // @Param: FLTMODE1 // @DisplayName: Flight Mode 1 - // @Description: Flight mode when Channel 5 pwm is <= 1230 + // @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is <= 1230 // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag,25:SystemID,26:Heli_Autorotate,27:Auto RTL // @User: Standard GSCALAR(flight_mode1, "FLTMODE1", (uint8_t)FLIGHT_MODE_1), // @Param: FLTMODE2 // @DisplayName: Flight Mode 2 - // @Description: Flight mode when Channel 5 pwm is >1230, <= 1360 + // @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1230, <= 1360 // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag,25:SystemID,26:Heli_Autorotate,27:Auto RTL // @User: Standard GSCALAR(flight_mode2, "FLTMODE2", (uint8_t)FLIGHT_MODE_2), // @Param: FLTMODE3 // @DisplayName: Flight Mode 3 - // @Description: Flight mode when Channel 5 pwm is >1360, <= 1490 + // @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1360, <= 1490 // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag,25:SystemID,26:Heli_Autorotate,27:Auto RTL // @User: Standard GSCALAR(flight_mode3, "FLTMODE3", (uint8_t)FLIGHT_MODE_3), // @Param: FLTMODE4 // @DisplayName: Flight Mode 4 - // @Description: Flight mode when Channel 5 pwm is >1490, <= 1620 + // @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1490, <= 1620 // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag,25:SystemID,26:Heli_Autorotate,27:Auto RTL // @User: Standard GSCALAR(flight_mode4, "FLTMODE4", (uint8_t)FLIGHT_MODE_4), // @Param: FLTMODE5 // @DisplayName: Flight Mode 5 - // @Description: Flight mode when Channel 5 pwm is >1620, <= 1749 + // @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1620, <= 1749 // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag,25:SystemID,26:Heli_Autorotate,27:Auto RTL // @User: Standard GSCALAR(flight_mode5, "FLTMODE5", (uint8_t)FLIGHT_MODE_5), // @Param: FLTMODE6 // @DisplayName: Flight Mode 6 - // @Description: Flight mode when Channel 5 pwm is >=1750 + // @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >=1750 // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag,25:SystemID,26:Heli_Autorotate,27:Auto RTL // @User: Standard GSCALAR(flight_mode6, "FLTMODE6", (uint8_t)FLIGHT_MODE_6),