mirror of https://github.com/ArduPilot/ardupilot
Copter: remove param docs for ACRO_RP_P and _YAW_RP
This commit is contained in:
parent
39a0ecbb4b
commit
13d1b8632b
|
@ -425,18 +425,6 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
// @User: Advanced
|
||||
GSCALAR(rc_speed, "RC_SPEED", RC_FAST_SPEED),
|
||||
|
||||
// @Param: ACRO_RP_P
|
||||
// @DisplayName: Acro Roll and Pitch P gain
|
||||
// @Description: Converts pilot roll and pitch into a desired rate of rotation in ACRO and SPORT mode. Higher values mean faster rate of rotation.
|
||||
// @Range: 1 10
|
||||
// @User: Standard
|
||||
|
||||
// @Param: ACRO_YAW_P
|
||||
// @DisplayName: Acro Yaw P gain
|
||||
// @Description: Converts pilot yaw input into a desired rate of rotation. Higher values mean faster rate of rotation.
|
||||
// @Range: 1 10
|
||||
// @User: Standard
|
||||
|
||||
#if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED
|
||||
// @Param: ACRO_BAL_ROLL
|
||||
// @DisplayName: Acro Balance Roll
|
||||
|
|
|
@ -362,7 +362,7 @@ public:
|
|||
k_param_pid_accel_z, // remove
|
||||
k_param_acro_balance_roll,
|
||||
k_param_acro_balance_pitch,
|
||||
k_param_acro_yaw_p,
|
||||
k_param_acro_yaw_p, // remove
|
||||
k_param_autotune_axis_bitmask, // remove
|
||||
k_param_autotune_aggressiveness, // remove
|
||||
k_param_pi_vel_xy, // remove
|
||||
|
|
Loading…
Reference in New Issue