mirror of https://github.com/ArduPilot/ardupilot
AP_GyroFFT: skip disabled notches
This commit is contained in:
parent
5bdac5174c
commit
97d42308a7
|
@ -253,7 +253,7 @@ void AP_GyroFFT::init(uint16_t loop_rate_hz)
|
||||||
uint8_t harmonics = 0;
|
uint8_t harmonics = 0;
|
||||||
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.enabled() && notch.params.tracking_mode() == HarmonicNotchDynamicMode::UpdateGyroFFT) {
|
||||||
harmonics |= notch.params.harmonics();
|
harmonics |= notch.params.harmonics();
|
||||||
num_notches = MAX(num_notches, notch.num_dynamic_notches);
|
num_notches = MAX(num_notches, notch.num_dynamic_notches);
|
||||||
}
|
}
|
||||||
|
@ -386,8 +386,10 @@ void AP_GyroFFT::update()
|
||||||
} else {
|
} else {
|
||||||
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.enabled()) {
|
||||||
num_notches = MAX(num_notches, notch.num_dynamic_notches);
|
num_notches = MAX(num_notches, notch.num_dynamic_notches);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
_health = MIN(_global_state._health, num_notches);
|
_health = MIN(_global_state._health, num_notches);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue