Browse Source

Plane: added ACRO mode to mode choices

master
Andrew Tridgell 12 years ago
parent
commit
11a4628409
  1. 14
      ArduPlane/Parameters.pde

14
ArduPlane/Parameters.pde

@ -317,7 +317,7 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -317,7 +317,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: THR_PASS_STAB
// @DisplayName: Throttle passthru in stabilize
// @Description: If this is set then when in STABILIZE or FBWA mode the throttle is a direct passthru from the transmitter. This means the THR_MIN and THR_MAX settings are not used in these modes. This is useful for petrol engines where you setup a throttle cut switch that suppresses the throttle below the normal minimum.
// @Description: If this is set then when in STABILIZE, FBWA or ACRO modes the throttle is a direct passthru from the transmitter. This means the THR_MIN and THR_MAX settings are not used in these modes. This is useful for petrol engines where you setup a throttle cut switch that suppresses the throttle below the normal minimum.
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
GSCALAR(throttle_passthru_stabilize,"THR_PASS_STAB", 0),
@ -398,7 +398,7 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -398,7 +398,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: FLTMODE1
// @DisplayName: FlightMode1
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,3:TRAINING,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,3:TRAINING,4:ACRO,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
// @User: Standard
// @Description: Flight mode for switch position 1 (910 to 1230 and above 2049)
GSCALAR(flight_mode1, "FLTMODE1", FLIGHT_MODE_1),
@ -406,35 +406,35 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -406,35 +406,35 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: FLTMODE2
// @DisplayName: FlightMode2
// @Description: Flight mode for switch position 2 (1231 to 1360)
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,3:TRAINING,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,3:TRAINING,4:ACRO,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
// @User: Standard
GSCALAR(flight_mode2, "FLTMODE2", FLIGHT_MODE_2),
// @Param: FLTMODE3
// @DisplayName: FlightMode3
// @Description: Flight mode for switch position 3 (1361 to 1490)
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,3:TRAINING,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,3:TRAINING,4:ACRO,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
// @User: Standard
GSCALAR(flight_mode3, "FLTMODE3", FLIGHT_MODE_3),
// @Param: FLTMODE4
// @DisplayName: FlightMode4
// @Description: Flight mode for switch position 4 (1491 to 1620)
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,3:TRAINING,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,3:TRAINING,4:ACRO,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
// @User: Standard
GSCALAR(flight_mode4, "FLTMODE4", FLIGHT_MODE_4),
// @Param: FLTMODE5
// @DisplayName: FlightMode5
// @Description: Flight mode for switch position 5 (1621 to 1749)
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,3:TRAINING,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,3:TRAINING,4:ACRO,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
// @User: Standard
GSCALAR(flight_mode5, "FLTMODE5", FLIGHT_MODE_5),
// @Param: FLTMODE6
// @DisplayName: FlightMode6
// @Description: Flight mode for switch position 6 (1750 to 2049)
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,3:TRAINING,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,3:TRAINING,4:ACRO,5:FBWA,6:FBWB,10:Auto,11:RTL,12:Loiter,15:Guided
// @User: Standard
GSCALAR(flight_mode6, "FLTMODE6", FLIGHT_MODE_6),

Loading…
Cancel
Save