mirror of https://github.com/ArduPilot/ardupilot
Filter: protect against extremely low notch filter frequencies
an incorrectly configured ESC telemetry source can lead to a notch running at very low frequencies. A simple example is a lua script like this: function update() esc_telem:update_rpm(12, 0, 0) return update, 10 end return update() where motor 12 is unused. with that script in place we get a 1.0078 Hz filter which leads to massive phase lag and a crashed aircraft this is a safety protection. We should also try to find out why the INS_HNTCH_FREQ lower limit is not working
This commit is contained in:
parent
73589a276e
commit
b79e96ab57
|
@ -71,7 +71,7 @@ void NotchFilter<T>::init_with_A_and_Q(float sample_freq_hz, float center_freq_h
|
|||
_center_freq_hz * NOTCH_MAX_SLEW_UPPER);
|
||||
}
|
||||
|
||||
if ((new_center_freq > 0.0) && (new_center_freq < 0.5 * sample_freq_hz) && (Q > 0.0)) {
|
||||
if ((new_center_freq > 2.0) && (new_center_freq < 0.5 * sample_freq_hz) && (Q > 0.0)) {
|
||||
float omega = 2.0 * M_PI * new_center_freq / sample_freq_hz;
|
||||
float alpha = sinf(omega) / (2 * Q);
|
||||
b0 = 1.0 + alpha*sq(A);
|
||||
|
|
Loading…
Reference in New Issue