Skip to content

Commit

Permalink
AP_InertialSensor: fixed check for changes to notch filters
Browse files Browse the repository at this point in the history
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
  • Loading branch information
tridge committed Nov 29, 2024
1 parent 5648795 commit 9a2ef4d
Showing 1 changed file with 1 addition and 2 deletions.
3 changes: 1 addition & 2 deletions libraries/AP_InertialSensor/AP_InertialSensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down

0 comments on commit 9a2ef4d

Please sign in to comment.