AC_AttControl_Heli: adjust rate gain param descriptions
This commit is contained in:
parent
35c6ea994d
commit
db04dddba5
@ -26,29 +26,28 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::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
|
||||
// @Range: 0.08 0.30
|
||||
// @Range: 0.08 0.35
|
||||
// @Increment: 0.005
|
||||
// @User: Standard
|
||||
|
||||
// @Param: RAT_RLL_I
|
||||
// @DisplayName: Roll axis rate controller I gain
|
||||
// @Description: Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate
|
||||
// @Range: 0.01 0.5
|
||||
// @Range: 0.01 0.6
|
||||
// @Increment: 0.01
|
||||
// @User: Standard
|
||||
|
||||
// @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
|
||||
// @Range: 0 4500
|
||||
// @Increment: 10
|
||||
// @Units: Percent*10
|
||||
// @Range: 0 1
|
||||
// @Increment: 0.01
|
||||
// @User: Standard
|
||||
|
||||
// @Param: RAT_RLL_D
|
||||
// @DisplayName: Roll axis rate controller D gain
|
||||
// @Description: Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate
|
||||
// @Range: 0.001 0.02
|
||||
// @Range: 0.001 0.03
|
||||
// @Increment: 0.001
|
||||
// @User: Standard
|
||||
|
||||
@ -56,34 +55,35 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
|
||||
// @DisplayName: Roll axis rate conroller input frequency in Hz
|
||||
// @Description: Roll axis rate conroller input frequency in Hz
|
||||
// @Unit: Hz
|
||||
// @Range: 1 20
|
||||
// @Increment: 1
|
||||
AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 2, AC_AttitudeControl_Heli, AC_HELI_PID),
|
||||
|
||||
// @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
|
||||
// @Range: 0.08 0.30
|
||||
// @Range: 0.08 0.35
|
||||
// @Increment: 0.005
|
||||
// @User: Standard
|
||||
|
||||
// @Param: RAT_PIT_I
|
||||
// @DisplayName: Pitch axis rate controller I gain
|
||||
// @Description: Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate
|
||||
// @Range: 0.01 0.5
|
||||
// @Range: 0.01 0.6
|
||||
// @Increment: 0.01
|
||||
// @User: Standard
|
||||
|
||||
// @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
|
||||
// @Range: 0 4500
|
||||
// @Increment: 10
|
||||
// @Units: Percent*10
|
||||
// @Range: 0 1
|
||||
// @Increment: 0.01
|
||||
// @User: Standard
|
||||
|
||||
// @Param: RAT_PIT_D
|
||||
// @DisplayName: Pitch axis rate controller D gain
|
||||
// @Description: Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate
|
||||
// @Range: 0.001 0.02
|
||||
// @Range: 0.001 0.03
|
||||
// @Increment: 0.001
|
||||
// @User: Standard
|
||||
|
||||
@ -91,28 +91,29 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
|
||||
// @DisplayName: Pitch axis rate conroller input frequency in Hz
|
||||
// @Description: Pitch axis rate conroller input frequency in Hz
|
||||
// @Unit: Hz
|
||||
// @Range: 1 20
|
||||
// @Increment: 1
|
||||
AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 3, AC_AttitudeControl_Heli, AC_HELI_PID),
|
||||
|
||||
// @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
|
||||
// @Range: 0.150 0.50
|
||||
// @Range: 0.180 0.60
|
||||
// @Increment: 0.005
|
||||
// @User: Standard
|
||||
|
||||
// @Param: RAT_YAW_I
|
||||
// @DisplayName: Yaw axis rate controller I gain
|
||||
// @Description: Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate
|
||||
// @Range: 0.010 0.05
|
||||
// @Range: 0.01 0.06
|
||||
// @Increment: 0.01
|
||||
// @User: Standard
|
||||
|
||||
// @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
|
||||
// @Range: 0 4500
|
||||
// @Increment: 10
|
||||
// @Units: Percent*10
|
||||
// @Range: 0 1
|
||||
// @Increment: 0.01
|
||||
// @User: Standard
|
||||
|
||||
// @Param: RAT_YAW_D
|
||||
@ -126,6 +127,8 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
|
||||
// @DisplayName: Yaw axis rate conroller input frequency in Hz
|
||||
// @Description: Yaw axis rate conroller input frequency in Hz
|
||||
// @Unit: Hz
|
||||
// @Range: 1 20
|
||||
// @Increment: 1
|
||||
AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 4, AC_AttitudeControl_Heli, AC_HELI_PID),
|
||||
|
||||
AP_GROUPEND
|
||||
|
Loading…
Reference in New Issue
Block a user