AC_AttitudeControl_Heli: fix VFF and ILMI param descriptions

This commit is contained in:
Randy Mackay 2020-02-13 18:17:01 +09:00
parent 043ba5cf34
commit e36d4d19e2

View File

@ -35,6 +35,12 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
// @Increment: 0.01 // @Increment: 0.01
// @User: Standard // @User: Standard
// @Param: RAT_RLL_ILMI
// @DisplayName: Roll axis rate controller I-term leak minimum
// @Description: Point below which I-term will not leak down
// @Range: 0 1
// @User: Advanced
// @Param: RAT_RLL_D // @Param: RAT_RLL_D
// @DisplayName: Roll axis rate controller D gain // @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 // @Description: Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate
@ -42,7 +48,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
// @Increment: 0.001 // @Increment: 0.001
// @User: Standard // @User: Standard
// @Param: RAT_RLL_FF // @Param: RAT_RLL_VFF
// @DisplayName: Roll axis rate controller feed forward // @DisplayName: Roll axis rate controller feed forward
// @Description: Roll axis rate controller feed forward // @Description: Roll axis rate controller feed forward
// @Range: 0 0.5 // @Range: 0 0.5
@ -95,6 +101,12 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
// @Increment: 0.01 // @Increment: 0.01
// @User: Standard // @User: Standard
// @Param: RAT_PIT_ILMI
// @DisplayName: Pitch axis rate controller I-term leak minimum
// @Description: Point below which I-term will not leak down
// @Range: 0 1
// @User: Advanced
// @Param: RAT_PIT_D // @Param: RAT_PIT_D
// @DisplayName: Pitch axis rate controller D gain // @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 // @Description: Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate
@ -102,7 +114,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
// @Increment: 0.001 // @Increment: 0.001
// @User: Standard // @User: Standard
// @Param: RAT_PIT_FF // @Param: RAT_PIT_VFF
// @DisplayName: Pitch axis rate controller feed forward // @DisplayName: Pitch axis rate controller feed forward
// @Description: Pitch axis rate controller feed forward // @Description: Pitch axis rate controller feed forward
// @Range: 0 0.5 // @Range: 0 0.5
@ -155,6 +167,12 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
// @Increment: 0.01 // @Increment: 0.01
// @User: Standard // @User: Standard
// @Param: RAT_YAW_ILMI
// @DisplayName: Yaw axis rate controller I-term leak minimum
// @Description: Point below which I-term will not leak down
// @Range: 0 1
// @User: Advanced
// @Param: RAT_YAW_D // @Param: RAT_YAW_D
// @DisplayName: Yaw axis rate controller D gain // @DisplayName: Yaw axis rate controller D gain
// @Description: Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate // @Description: Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate
@ -162,7 +180,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
// @Increment: 0.001 // @Increment: 0.001
// @User: Standard // @User: Standard
// @Param: RAT_YAW_FF // @Param: RAT_YAW_VFF
// @DisplayName: Yaw axis rate controller feed forward // @DisplayName: Yaw axis rate controller feed forward
// @Description: Yaw axis rate controller feed forward // @Description: Yaw axis rate controller feed forward
// @Range: 0 0.5 // @Range: 0 0.5