From c78dcb15a1b7c6c107296a4b66047ab43d0f603b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 7 Sep 2020 11:53:52 +1000 Subject: [PATCH] AC_PID: remove dead get_ff(float target) method as per TODO comment --- libraries/AC_PID/AC_PID.cpp | 8 -------- libraries/AC_PID/AC_PID.h | 3 --- 2 files changed, 11 deletions(-) diff --git a/libraries/AC_PID/AC_PID.cpp b/libraries/AC_PID/AC_PID.cpp index 8ea4a5fb09..5d4cb202db 100644 --- a/libraries/AC_PID/AC_PID.cpp +++ b/libraries/AC_PID/AC_PID.cpp @@ -236,14 +236,6 @@ float AC_PID::get_ff() return _target * _kff; } -// todo: remove function when it is no longer used. -float AC_PID::get_ff(float target) -{ - float FF_out = (target * _kff); - _pid_info.FF = FF_out; - return FF_out; -} - void AC_PID::reset_I() { _integrator = 0; diff --git a/libraries/AC_PID/AC_PID.h b/libraries/AC_PID/AC_PID.h index 631eb1c28f..b83df07aad 100644 --- a/libraries/AC_PID/AC_PID.h +++ b/libraries/AC_PID/AC_PID.h @@ -50,9 +50,6 @@ public: float get_d() const; float get_ff(); - // todo: remove function when it is no longer used. - float get_ff(float target); - // reset_I - reset the integrator void reset_I();