AC_AttitudeControl: remove % as units on params that are unitless

This commit is contained in:
Hwurzburg 2021-05-27 21:26:29 -05:00 committed by Tom Pittenger
parent bf14c32109
commit 27620322ec
2 changed files with 0 additions and 6 deletions

View File

@ -26,7 +26,6 @@ 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: %
// @User: Standard
// @Param: RAT_RLL_D
@ -95,7 +94,6 @@ 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: %
// @User: Standard
// @Param: RAT_PIT_D
@ -164,7 +162,6 @@ 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: %
// @User: Standard
// @Param: RAT_YAW_D

View File

@ -26,7 +26,6 @@ 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: %
// @User: Standard
// @Param: RAT_RLL_D
@ -95,7 +94,6 @@ 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: %
// @User: Standard
// @Param: RAT_PIT_D
@ -164,7 +162,6 @@ 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: %
// @User: Standard
// @Param: RAT_YAW_D