From b1d6e41fb97cf5546a7fdfc9ec468ce253f8fde1 Mon Sep 17 00:00:00 2001 From: Bill Geyer Date: Tue, 1 Feb 2022 18:46:30 -0500 Subject: [PATCH] AC_PID: tradheli-change param name from _VFF to _FF --- libraries/AC_PID/AC_HELI_PID.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AC_PID/AC_HELI_PID.cpp b/libraries/AC_PID/AC_HELI_PID.cpp index 910e9dc85f..9236c01568 100644 --- a/libraries/AC_PID/AC_HELI_PID.cpp +++ b/libraries/AC_PID/AC_HELI_PID.cpp @@ -22,10 +22,10 @@ const AP_Param::GroupInfo AC_HELI_PID::var_info[] = { // 3 was for uint16 IMAX - // @Param: VFF - // @DisplayName: Velocity FF FeedForward Gain - // @Description: Velocity FF Gain which produces an output value that is proportional to the demanded input - AP_GROUPINFO("VFF", 4, AC_HELI_PID, _kff, 0), + // @Param: FF + // @DisplayName: FF FeedForward Gain + // @Description: FF Gain which produces an output value that is proportional to the demanded input + AP_GROUPINFO("FF", 4, AC_HELI_PID, _kff, 0), // @Param: IMAX // @DisplayName: PID Integral Maximum