mirror of https://github.com/ArduPilot/ardupilot
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:
parent
564879594e
commit
53ee7d6e75
|
@ -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()) ||
|
if (!is_equal(last_bandwidth_hz[instance], params.bandwidth_hz()) ||
|
||||||
!is_equal(last_attenuation_dB[instance], params.attenuation_dB()) ||
|
!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) {
|
converging) {
|
||||||
filter[instance].init(gyro_rate, params);
|
filter[instance].init(gyro_rate, params);
|
||||||
last_center_freq_hz[instance] = params.center_freq_hz();
|
last_center_freq_hz[instance] = params.center_freq_hz();
|
||||||
|
|
Loading…
Reference in New Issue