mirror of https://github.com/ArduPilot/ardupilot
Changing TradHeli param motors.acro_mode to motors.flybar_mode to better reflect it's intent.
This commit is contained in:
parent
ab0559359d
commit
3d0ef1b3e6
|
@ -153,12 +153,12 @@ const AP_Param::GroupInfo AP_MotorsHeli::var_info[] PROGMEM = {
|
|||
// @User: Standard
|
||||
AP_GROUPINFO("RSC_RATE", 17, AP_MotorsHeli, rsc_ramp_up_rate, 1000),
|
||||
|
||||
// @Param: ACRO_MODE
|
||||
// @DisplayName: Acro Mode Selector
|
||||
// @Description: This sets which acro mode is active. (1) is Flybarless (2) is Flybarred Pass-Through
|
||||
// @Range: 1 2
|
||||
// @Param: FLYBAR_MODE
|
||||
// @DisplayName: Flybar Mode Selector
|
||||
// @Description: This sets which acro mode is active. (0) is Flybarless (1) is Mechanical Flybar
|
||||
// @Range: 0 1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("ACRO_MODE", 18, AP_MotorsHeli, acro_mode, 1),
|
||||
AP_GROUPINFO("FLYBAR_MODE", 18, AP_MotorsHeli, flybar_mode, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
|
|
@ -95,7 +95,7 @@ public:
|
|||
AP_Int16 ext_gov_setpoint; // maximum output to the motor governor
|
||||
AP_Int8 rsc_mode; // sets the mode for rotor speed controller
|
||||
AP_Int16 rsc_ramp_up_rate; // sets the time in 100th seconds the RSC takes to ramp up to speed
|
||||
AP_Int8 acro_mode; // selects FBL Acro Mode, or Flybarred Acro Mode
|
||||
AP_Int8 flybar_mode; // selects FBL Acro Mode, or Flybarred Acro Mode
|
||||
int16_t throttle_mid; // throttle mid point in pwm form (i.e. 0 ~ 1000)
|
||||
|
||||
|
||||
|
|
Loading…
Reference in New Issue