From ead3682e4c671c72c0245dc891ec58f8b5d05fec Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 5 Mar 2019 21:09:49 +0900 Subject: [PATCH] Copter: correct ACRO_YAW_P param description this parameter applies to all flight modes --- ArduCopter/Parameters.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 28ae87a981..bbdf372399 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -448,7 +448,7 @@ const AP_Param::Info Copter::var_info[] = { // @Param: ACRO_YAW_P // @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 // @User: Standard GSCALAR(acro_yaw_p, "ACRO_YAW_P", ACRO_YAW_P),