AP_InertialSensor: fixed check for changes to notch filters

if the configured freq changes on any type of notch then A and Q
change, so init must be called. This does not affect only Fixed
notches
This commit is contained in:
Andrew Tridgell 2024-11-30 07:28:06 +11:00
parent 564879594e
commit 53ee7d6e75
1 changed files with 1 additions and 2 deletions

View File

@ -1863,8 +1863,7 @@ void AP_InertialSensor::HarmonicNotch::update_params(uint8_t instance, bool conv
{
if (!is_equal(last_bandwidth_hz[instance], params.bandwidth_hz()) ||
!is_equal(last_attenuation_dB[instance], params.attenuation_dB()) ||
(params.tracking_mode() == HarmonicNotchDynamicMode::Fixed &&
!is_equal(last_center_freq_hz[instance], params.center_freq_hz())) ||
!is_equal(last_center_freq_hz[instance], params.center_freq_hz()) ||
converging) {
filter[instance].init(gyro_rate, params);
last_center_freq_hz[instance] = params.center_freq_hz();