mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AC_PID: use calc_lowpass_alpha_dt()
This commit is contained in:
parent
b0f0c8d842
commit
9e73922fd9
@ -325,13 +325,7 @@ float AC_PID::get_filt_D_alpha() const
|
||||
// get_filt_alpha - calculate a filter alpha
|
||||
float AC_PID::get_filt_alpha(float filt_hz) const
|
||||
{
|
||||
if (is_zero(filt_hz)) {
|
||||
return 1.0f;
|
||||
}
|
||||
|
||||
// calculate alpha
|
||||
float rc = 1 / (M_2PI * filt_hz);
|
||||
return _dt / (_dt + rc);
|
||||
return calc_lowpass_alpha_dt(_dt, filt_hz);
|
||||
}
|
||||
|
||||
void AC_PID::set_integrator(float target, float measurement, float i)
|
||||
|
Loading…
Reference in New Issue
Block a user