AR_AttitudeControl: fix parameter descriptions

This commit is contained in:
Randy Mackay 2017-12-11 17:01:18 +09:00
parent c17549c7ff
commit cabced82f1

View File

@ -42,13 +42,20 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
// @Increment: 0.01
// @User: Standard
// @Param: _STR_RATE_D
// @Param: _STR_RAT_D
// @DisplayName: Steering control D gain
// @Description: Steering control D gain. Compensates for short-term change in desired turn rate vs actual
// @Range: 0.000 0.400
// @Increment: 0.001
// @User: Standard
// @Param: _STR_RAT_FF
// @DisplayName: Steering control feed forward
// @Description: Steering control feed forward
// @Range: 0 0.5
// @Increment: 0.001
// @User: Standard
// @Param: _STR_RAT_FILT
// @DisplayName: Steering control filter frequency
// @Description: Steering control input filter. Lower values reduce noise but add delay.
@ -85,6 +92,13 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = {
// @Increment: 0.001
// @User: Standard
// @Param: _SPEED_FF
// @DisplayName: Speed control feed forward
// @Description: Speed control feed forward
// @Range: 0 0.5
// @Increment: 0.001
// @User: Standard
// @Param: _SPEED_FILT
// @DisplayName: Speed control filter frequency
// @Description: Speed control input filter. Lower values reduce noise but add delay.