mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: correct ACRO_YAW_P param description
this parameter applies to all flight modes
This commit is contained in:
parent
938868cc03
commit
ead3682e4c
@ -448,7 +448,7 @@ const AP_Param::Info Copter::var_info[] = {
|
|||||||
|
|
||||||
// @Param: ACRO_YAW_P
|
// @Param: ACRO_YAW_P
|
||||||
// @DisplayName: Acro Yaw P gain
|
// @DisplayName: Acro Yaw P gain
|
||||||
// @Description: Converts pilot yaw input into a desired rate of rotation in ACRO, Stabilize and SPORT modes. Higher values mean faster rate of rotation.
|
// @Description: Converts pilot yaw input into a desired rate of rotation. Higher values mean faster rate of rotation.
|
||||||
// @Range: 1 10
|
// @Range: 1 10
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(acro_yaw_p, "ACRO_YAW_P", ACRO_YAW_P),
|
GSCALAR(acro_yaw_p, "ACRO_YAW_P", ACRO_YAW_P),
|
||||||
|
Loading…
Reference in New Issue
Block a user