From 0d52cd4aebf62b2404a04a07d35fff8f51c174cc Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Tue, 3 Aug 2021 13:35:35 +0930 Subject: [PATCH] AC_AttitudeControl: AC_PosControl: fix PID filter names FILT -> FLTE, D_FILT -> FLTD --- libraries/AC_AttitudeControl/AC_PosControl.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index 94d2528674..cca0a6a71d 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -239,14 +239,14 @@ const AP_Param::GroupInfo AC_PosControl::var_info[] = { // @Units: cm/s/s // @User: Advanced - // @Param: _VELXY_FILT + // @Param: _VELXY_FLTE // @DisplayName: Velocity (horizontal) input filter // @Description: Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for P and I terms // @Range: 0 100 // @Units: Hz // @User: Advanced - // @Param: _VELXY_D_FILT + // @Param: _VELXY_FLTD // @DisplayName: Velocity (horizontal) input filter // @Description: Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for D term // @Range: 0 100