mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_GyroFFT: allow for 2 FFT based notches
This commit is contained in:
parent
301c56d30a
commit
492e203fd2
@ -254,9 +254,8 @@ void AP_GyroFFT::init(uint16_t loop_rate_hz)
|
|||||||
uint8_t num_notches = 0;
|
uint8_t num_notches = 0;
|
||||||
for (auto ¬ch : _ins->harmonic_notches) {
|
for (auto ¬ch : _ins->harmonic_notches) {
|
||||||
if (notch.params.tracking_mode() == HarmonicNotchDynamicMode::UpdateGyroFFT) {
|
if (notch.params.tracking_mode() == HarmonicNotchDynamicMode::UpdateGyroFFT) {
|
||||||
harmonics = notch.params.harmonics();
|
harmonics |= notch.params.harmonics();
|
||||||
num_notches = notch.num_dynamic_notches;
|
num_notches = MAX(num_notches, notch.num_dynamic_notches);
|
||||||
break;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// count the number of active harmonics or dynamic notchs
|
// count the number of active harmonics or dynamic notchs
|
||||||
|
Loading…
Reference in New Issue
Block a user