mirror of https://github.com/ArduPilot/ardupilot
AC_PID: remove unused set_integrator methods
This commit is contained in:
parent
2d75b0312e
commit
9146458d4a
|
@ -402,16 +402,6 @@ float AC_PID::get_filt_D_alpha(float dt) const
|
|||
return calc_lowpass_alpha_dt(dt, _filt_D_hz);
|
||||
}
|
||||
|
||||
void AC_PID::set_integrator(float target, float measurement, float integrator)
|
||||
{
|
||||
set_integrator(target - measurement, integrator);
|
||||
}
|
||||
|
||||
void AC_PID::set_integrator(float error, float integrator)
|
||||
{
|
||||
_integrator = constrain_float(integrator - error * _kp, -_kimax, _kimax);
|
||||
}
|
||||
|
||||
void AC_PID::set_integrator(float integrator)
|
||||
{
|
||||
_integrator = constrain_float(integrator, -_kimax, _kimax);
|
||||
|
|
|
@ -134,8 +134,6 @@ public:
|
|||
void set_actual_rate(float actual) { _pid_info.actual = actual; }
|
||||
|
||||
// integrator setting functions
|
||||
void set_integrator(float target, float measurement, float i);
|
||||
void set_integrator(float error, float i);
|
||||
void set_integrator(float i);
|
||||
void relax_integrator(float integrator, float dt, float time_constant);
|
||||
|
||||
|
|
Loading…
Reference in New Issue