From 692e6518cc2eeef7f2eea7879060637c258ac9df Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Fri, 5 Jan 2018 21:19:14 +1030 Subject: [PATCH] AC_AttitudeControl: update param desc values for large copters --- libraries/AC_AttitudeControl/AC_AttitudeControl.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp index da2831215a..cb3568d83b 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp @@ -23,7 +23,7 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = { // @Description: Maximum acceleration in yaw axis // @Units: cdeg/s/s // @Range: 0 72000 - // @Values: 0:Disabled, 18000:Slow, 36000:Medium, 54000:Fast + // @Values: 0:Disabled, 9000:VerySlow, 18000:Slow, 36000:Medium, 54000:Fast // @Increment: 1000 // @User: Advanced AP_GROUPINFO("ACCEL_Y_MAX", 4, AC_AttitudeControl, _accel_yaw_max, AC_ATTITUDE_CONTROL_ACCEL_Y_MAX_DEFAULT_CDSS), @@ -41,7 +41,7 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = { // @Units: cdeg/s/s // @Range: 0 180000 // @Increment: 1000 - // @Values: 0:Disabled, 72000:Slow, 108000:Medium, 162000:Fast + // @Values: 0:Disabled, 30000:VerySlow, 72000:Slow, 108000:Medium, 162000:Fast // @User: Advanced AP_GROUPINFO("ACCEL_R_MAX", 6, AC_AttitudeControl, _accel_roll_max, AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT_CDSS), @@ -51,7 +51,7 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = { // @Units: cdeg/s/s // @Range: 0 180000 // @Increment: 1000 - // @Values: 0:Disabled, 72000:Slow, 108000:Medium, 162000:Fast + // @Values: 0:Disabled, 30000:VerySlow, 72000:Slow, 108000:Medium, 162000:Fast // @User: Advanced AP_GROUPINFO("ACCEL_P_MAX", 7, AC_AttitudeControl, _accel_pitch_max, AC_ATTITUDE_CONTROL_ACCEL_RP_MAX_DEFAULT_CDSS),