From 86db91e3b456aa7abebddbdd7b8082311fd830d3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 15 Apr 2022 17:39:30 +1000 Subject: [PATCH] AP_GyroFFT: use HarmonicNotch class --- libraries/AP_GyroFFT/AP_GyroFFT.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_GyroFFT/AP_GyroFFT.cpp b/libraries/AP_GyroFFT/AP_GyroFFT.cpp index 28b57e63f9..91c93bd5e4 100644 --- a/libraries/AP_GyroFFT/AP_GyroFFT.cpp +++ b/libraries/AP_GyroFFT/AP_GyroFFT.cpp @@ -252,10 +252,10 @@ void AP_GyroFFT::init(uint16_t loop_rate_hz) // note that we only allow one harmonic notch filter linked to the FFT code uint8_t harmonics = 0; uint8_t num_notches = 0; - for (uint8_t i=0; iget_gyro_harmonic_notch_tracking_mode(i) == HarmonicNotchDynamicMode::UpdateGyroFFT) { - harmonics = _ins->get_gyro_harmonic_notch_harmonics(i); - num_notches = _ins->get_num_gyro_dynamic_notches(i); + for (auto ¬ch : _ins->harmonic_notches) { + if (notch.params.tracking_mode() == HarmonicNotchDynamicMode::UpdateGyroFFT) { + harmonics = notch.params.harmonics(); + num_notches = notch.num_dynamic_notches; break; } } @@ -385,8 +385,8 @@ void AP_GyroFFT::update() _health = 0; } else { uint8_t num_notches = 0; - for (uint8_t i=0; iget_num_gyro_dynamic_notches(i)); + for (auto ¬ch : _ins->harmonic_notches) { + num_notches = MAX(num_notches, notch.num_dynamic_notches); } _health = MIN(_global_state._health, num_notches); }