mirror of https://github.com/ArduPilot/ardupilot
AC_CustomControl: generalize pid descriptions
This commit is contained in:
parent
b9452e58b7
commit
33c45c8b12
|
@ -31,7 +31,7 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = {
|
|||
|
||||
// @Param: RAT_RLL_P
|
||||
// @DisplayName: Roll axis rate controller P gain
|
||||
// @Description: Roll axis rate controller P gain. Converts the difference between desired roll rate and actual roll rate into a motor speed output
|
||||
// @Description: Roll axis rate controller P gain. Corrects in proportion to the difference between the desired roll rate vs actual roll rate
|
||||
// @Range: 0.01 0.5
|
||||
// @Increment: 0.005
|
||||
// @User: Standard
|
||||
|
@ -45,7 +45,7 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = {
|
|||
|
||||
// @Param: RAT_RLL_IMAX
|
||||
// @DisplayName: Roll axis rate controller I gain maximum
|
||||
// @Description: Roll axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
|
||||
// @Description: Roll axis rate controller I gain maximum. Constrains the maximum that the I term will output
|
||||
// @Range: 0 1
|
||||
// @Increment: 0.01
|
||||
// @User: Standard
|
||||
|
@ -98,7 +98,7 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = {
|
|||
|
||||
// @Param: RAT_PIT_P
|
||||
// @DisplayName: Pitch axis rate controller P gain
|
||||
// @Description: Pitch axis rate controller P gain. Converts the difference between desired pitch rate and actual pitch rate into a motor speed output
|
||||
// @Description: Pitch axis rate controller P gain. Corrects in proportion to the difference between the desired pitch rate vs actual pitch rate
|
||||
// @Range: 0.01 0.50
|
||||
// @Increment: 0.005
|
||||
// @User: Standard
|
||||
|
@ -112,7 +112,7 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = {
|
|||
|
||||
// @Param: RAT_PIT_IMAX
|
||||
// @DisplayName: Pitch axis rate controller I gain maximum
|
||||
// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
|
||||
// @Description: Pitch axis rate controller I gain maximum. Constrains the maximum that the I term will output
|
||||
// @Range: 0 1
|
||||
// @Increment: 0.01
|
||||
// @User: Standard
|
||||
|
@ -166,7 +166,7 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = {
|
|||
|
||||
// @Param: RAT_YAW_P
|
||||
// @DisplayName: Yaw axis rate controller P gain
|
||||
// @Description: Yaw axis rate controller P gain. Converts the difference between desired yaw rate and actual yaw rate into a motor speed output
|
||||
// @Description: Yaw axis rate controller P gain. Corrects in proportion to the difference between the desired yaw rate vs actual yaw rate
|
||||
// @Range: 0.10 2.50
|
||||
// @Increment: 0.005
|
||||
// @User: Standard
|
||||
|
@ -180,7 +180,7 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = {
|
|||
|
||||
// @Param: RAT_YAW_IMAX
|
||||
// @DisplayName: Yaw axis rate controller I gain maximum
|
||||
// @Description: Yaw axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
|
||||
// @Description: Yaw axis rate controller I gain maximum. Constrains the maximum that the I term will output
|
||||
// @Range: 0 1
|
||||
// @Increment: 0.01
|
||||
// @User: Standard
|
||||
|
|
Loading…
Reference in New Issue