AC_AttitudeControl: Use SI units conventions in parameter units

Follow the rules from:
http://physics.nist.gov/cuu/Units/units.html
http://physics.nist.gov/cuu/Units/outside.html
and
http://physics.nist.gov/cuu/Units/checklist.html
one further constrain is that only printable (7bit) ASCII characters are allowed
This commit is contained in:
Dr.-Ing. Amilcar Do Carmo Lucas 2017-05-02 15:37:20 +02:00 committed by Andrew Tridgell
parent b996bb4a5d
commit 188dfb6936
4 changed files with 11 additions and 11 deletions

View File

@ -10,7 +10,7 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = {
// @Param: SLEW_YAW
// @DisplayName: Yaw target slew rate
// @Description: Maximum rate the yaw target can be updated in Loiter, RTL, Auto flight modes
// @Units: Centi-Degrees/Sec
// @Units: cdeg/s
// @Range: 500 18000
// @Increment: 100
// @User: Advanced
@ -21,7 +21,7 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = {
// @Param: ACCEL_Y_MAX
// @DisplayName: Acceleration Max for Yaw
// @Description: Maximum acceleration in yaw axis
// @Units: Centi-Degrees/Sec/Sec
// @Units: cdeg/s/s
// @Range: 0 72000
// @Values: 0:Disabled, 18000:Slow, 36000:Medium, 54000:Fast
// @Increment: 1000
@ -38,7 +38,7 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = {
// @Param: ACCEL_R_MAX
// @DisplayName: Acceleration Max for Roll
// @Description: Maximum acceleration in roll axis
// @Units: Centi-Degrees/Sec/Sec
// @Units: cdeg/s/s
// @Range: 0 180000
// @Increment: 1000
// @Values: 0:Disabled, 72000:Slow, 108000:Medium, 162000:Fast
@ -48,7 +48,7 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = {
// @Param: ACCEL_P_MAX
// @DisplayName: Acceleration Max for Pitch
// @Description: Maximum acceleration in pitch axis
// @Units: Centi-Degrees/Sec/Sec
// @Units: cdeg/s/s
// @Range: 0 180000
// @Increment: 1000
// @Values: 0:Disabled, 72000:Slow, 108000:Medium, 162000:Fast

View File

@ -16,7 +16,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
// @Param: HOVR_ROL_TRM
// @DisplayName: Hover Roll Trim
// @Description: Trim the hover roll angle to counter tail rotor thrust in a hover
// @Units: Centi-Degrees
// @Units: cdeg
// @Range: 0 1000
// @User: Advanced
AP_GROUPINFO("HOVR_ROL_TRM", 1, AC_AttitudeControl_Heli, _hover_roll_trim, AC_ATTITUDE_HELI_HOVER_ROLL_TRIM_DEFAULT),

View File

@ -26,7 +26,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = {
// @Description: Roll axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
// @Range: 0 1
// @Increment: 0.01
// @Units: Percent
// @Units: %
// @User: Standard
// @Param: RAT_RLL_D
@ -71,7 +71,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = {
// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
// @Range: 0 1
// @Increment: 0.01
// @Units: Percent
// @Units: %
// @User: Standard
// @Param: RAT_PIT_D
@ -116,7 +116,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = {
// @Description: Yaw axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
// @Range: 0 1
// @Increment: 0.01
// @Units: Percent
// @Units: %
// @User: Standard
// @Param: RAT_YAW_D

View File

@ -26,7 +26,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = {
// @Description: Roll axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
// @Range: 0 1
// @Increment: 0.01
// @Units: Percent
// @Units: %
// @User: Standard
// @Param: RAT_RLL_D
@ -71,7 +71,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = {
// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
// @Range: 0 1
// @Increment: 0.01
// @Units: Percent
// @Units: %
// @User: Standard
// @Param: RAT_PIT_D
@ -116,7 +116,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = {
// @Description: Yaw axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
// @Range: 0 1
// @Increment: 0.01
// @Units: Percent
// @Units: %
// @User: Standard
// @Param: RAT_YAW_D