AP_GyroFFT: allow for 2 FFT based notches

This commit is contained in:
Andrew Tridgell 2022-04-15 18:56:15 +10:00 committed by Randy Mackay
parent 8fb1d56dfe
commit a15259d7e5
1 changed files with 2 additions and 3 deletions

View File

@ -254,9 +254,8 @@ void AP_GyroFFT::init(uint16_t loop_rate_hz)
uint8_t num_notches = 0;
for (auto &notch : _ins->harmonic_notches) {
if (notch.params.tracking_mode() == HarmonicNotchDynamicMode::UpdateGyroFFT) {
harmonics = notch.params.harmonics();
num_notches = notch.num_dynamic_notches;
break;
harmonics |= notch.params.harmonics();
num_notches = MAX(num_notches, notch.num_dynamic_notches);
}
}