mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_AttitudeControl_Heli: fix VFF and ILMI param descriptions
This commit is contained in:
parent
043ba5cf34
commit
e36d4d19e2
@ -35,6 +35,12 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
|
||||
// @Increment: 0.01
|
||||
// @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
|
||||
// @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
|
||||
@ -42,7 +48,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
|
||||
// @Increment: 0.001
|
||||
// @User: Standard
|
||||
|
||||
// @Param: RAT_RLL_FF
|
||||
// @Param: RAT_RLL_VFF
|
||||
// @DisplayName: Roll axis rate controller feed forward
|
||||
// @Description: Roll axis rate controller feed forward
|
||||
// @Range: 0 0.5
|
||||
@ -95,6 +101,12 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
|
||||
// @Increment: 0.01
|
||||
// @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
|
||||
// @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
|
||||
@ -102,7 +114,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
|
||||
// @Increment: 0.001
|
||||
// @User: Standard
|
||||
|
||||
// @Param: RAT_PIT_FF
|
||||
// @Param: RAT_PIT_VFF
|
||||
// @DisplayName: Pitch axis rate controller feed forward
|
||||
// @Description: Pitch axis rate controller feed forward
|
||||
// @Range: 0 0.5
|
||||
@ -155,6 +167,12 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
|
||||
// @Increment: 0.01
|
||||
// @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
|
||||
// @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
|
||||
@ -162,7 +180,7 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = {
|
||||
// @Increment: 0.001
|
||||
// @User: Standard
|
||||
|
||||
// @Param: RAT_YAW_FF
|
||||
// @Param: RAT_YAW_VFF
|
||||
// @DisplayName: Yaw axis rate controller feed forward
|
||||
// @Description: Yaw axis rate controller feed forward
|
||||
// @Range: 0 0.5
|
||||
|
Loading…
Reference in New Issue
Block a user