AC_PosControl: correct VELXY_D_FILT Description

This commit is contained in:
Iampete1 2020-06-23 00:29:14 +01:00 committed by Randy Mackay
parent c53d42e665
commit c27bdafea4

View File

@ -191,7 +191,7 @@ const AP_Param::GroupInfo AC_PosControl::var_info[] = {
// @Param: _VELXY_D_FILT
// @DisplayName: Velocity (horizontal) input filter
// @Description: Velocity (horizontal) input filter. This filter (in hz) is applied to the input for P and I terms
// @Description: Velocity (horizontal) input filter. This filter (in hz) is applied to the input for D term
// @Range: 0 100
// @Units: Hz
// @User: Advanced