mirror of https://github.com/ArduPilot/ardupilot
Sub: Reduce flight mode parameter options.
This commit is contained in:
parent
9534f41a53
commit
1633ffb4e4
|
@ -314,42 +314,42 @@ const AP_Param::Info Sub::var_info[] = {
|
|||
// @Param: FLTMODE1
|
||||
// @DisplayName: Flight Mode 1
|
||||
// @Description: Flight mode when Channel 5 pwm is <= 1230
|
||||
// @Values: 0:Stabilize,1:Acro,2:DepthHold,3:Auto,16:PosHold,19:Manual
|
||||
// @Values: 0:Stabilize,2:DepthHold,19:Manual
|
||||
// @User: Standard
|
||||
GSCALAR(flight_mode1, "FLTMODE1", FLIGHT_MODE_1),
|
||||
|
||||
// @Param: FLTMODE2
|
||||
// @DisplayName: Flight Mode 2
|
||||
// @Description: Flight mode when Channel 5 pwm is >1230, <= 1360
|
||||
// @Values: 0:Stabilize,1:Acro,2:DepthHold,3:Auto,16:PosHold,19:Manual
|
||||
// @Values: 0:Stabilize,2:DepthHold,19:Manual
|
||||
// @User: Standard
|
||||
GSCALAR(flight_mode2, "FLTMODE2", FLIGHT_MODE_2),
|
||||
|
||||
// @Param: FLTMODE3
|
||||
// @DisplayName: Flight Mode 3
|
||||
// @Description: Flight mode when Channel 5 pwm is >1360, <= 1490
|
||||
// @Values: 0:Stabilize,1:Acro,2:DepthHold,3:Auto,16:PosHold,19:Manual
|
||||
// @Values: 0:Stabilize,2:DepthHold,19:Manual
|
||||
// @User: Standard
|
||||
GSCALAR(flight_mode3, "FLTMODE3", FLIGHT_MODE_3),
|
||||
|
||||
// @Param: FLTMODE4
|
||||
// @DisplayName: Flight Mode 4
|
||||
// @Description: Flight mode when Channel 5 pwm is >1490, <= 1620
|
||||
// @Values: 0:Stabilize,1:Acro,2:DepthHold,3:Auto,16:PosHold,19:Manual
|
||||
// @Values: 0:Stabilize,2:DepthHold,19:Manual
|
||||
// @User: Standard
|
||||
GSCALAR(flight_mode4, "FLTMODE4", FLIGHT_MODE_4),
|
||||
|
||||
// @Param: FLTMODE5
|
||||
// @DisplayName: Flight Mode 5
|
||||
// @Description: Flight mode when Channel 5 pwm is >1620, <= 1749
|
||||
// @Values: 0:Stabilize,1:Acro,2:DepthHold,3:Auto,16:PosHold,19:Manual
|
||||
// @Values: 0:Stabilize,2:DepthHold,19:Manual
|
||||
// @User: Standard
|
||||
GSCALAR(flight_mode5, "FLTMODE5", FLIGHT_MODE_5),
|
||||
|
||||
// @Param: FLTMODE6
|
||||
// @DisplayName: Flight Mode 6
|
||||
// @Description: Flight mode when Channel 5 pwm is >=1750
|
||||
// @Values: 0:Stabilize,1:Acro,2:DepthHold,3:Auto,16:PosHold,19:Manual
|
||||
// @Values: 0:Stabilize,2:DepthHold,19:Manual
|
||||
// @User: Standard
|
||||
GSCALAR(flight_mode6, "FLTMODE6", FLIGHT_MODE_6),
|
||||
|
||||
|
|
Loading…
Reference in New Issue