mirror of https://github.com/ArduPilot/ardupilot
Filter: only update notch on init if fixed
This commit is contained in:
parent
1ef89d31f2
commit
9726e8e218
|
@ -191,8 +191,11 @@ void HarmonicNotchFilter<T>::init(float sample_freq_hz, HarmonicNotchFilterParam
|
||||||
NotchFilter<T>::calculate_A_and_Q(center_freq_hz, bandwidth_hz / _composite_notches, attenuation_dB, _A, _Q);
|
NotchFilter<T>::calculate_A_and_Q(center_freq_hz, bandwidth_hz / _composite_notches, attenuation_dB, _A, _Q);
|
||||||
|
|
||||||
_initialised = true;
|
_initialised = true;
|
||||||
|
|
||||||
// ensure static notches are allocated and working
|
// ensure static notches are allocated and working
|
||||||
|
if (params->tracking_mode() == HarmonicNotchDynamicMode::Fixed) {
|
||||||
update(center_freq_hz);
|
update(center_freq_hz);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
Loading…
Reference in New Issue