mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_GyroFFT: allow for 2 FFT based notches
This commit is contained in:
parent
975fc6b70d
commit
66ad3051c3
@ -254,9 +254,8 @@ void AP_GyroFFT::init(uint16_t loop_rate_hz)
|
||||
uint8_t num_notches = 0;
|
||||
for (auto ¬ch : _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);
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user