Browse Source

AC_PID: remove dead get_ff(float target) method as per TODO comment

zr-v5.1
Peter Barker 4 years ago committed by Randy Mackay
parent
commit
c78dcb15a1
  1. 8
      libraries/AC_PID/AC_PID.cpp
  2. 3
      libraries/AC_PID/AC_PID.h

8
libraries/AC_PID/AC_PID.cpp

@ -236,14 +236,6 @@ float AC_PID::get_ff()
return _target * _kff; 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() void AC_PID::reset_I()
{ {
_integrator = 0; _integrator = 0;

3
libraries/AC_PID/AC_PID.h

@ -50,9 +50,6 @@ public:
float get_d() const; float get_d() const;
float get_ff(); float get_ff();
// todo: remove function when it is no longer used.
float get_ff(float target);
// reset_I - reset the integrator // reset_I - reset the integrator
void reset_I(); void reset_I();

Loading…
Cancel
Save