AP_RPM: use HarmonicNotch class

This commit is contained in:
Andrew Tridgell 2022-04-15 17:39:30 +10:00
parent 5080c32197
commit f8c1c39868
1 changed files with 4 additions and 4 deletions

View File

@ -32,10 +32,10 @@ AP_RPM_HarmonicNotch::AP_RPM_HarmonicNotch(AP_RPM &_ap_rpm, uint8_t _instance, A
void AP_RPM_HarmonicNotch::update(void) void AP_RPM_HarmonicNotch::update(void)
{ {
AP_InertialSensor& ins = AP::ins(); AP_InertialSensor& ins = AP::ins();
for (uint8_t i=0; i<HAL_INS_NUM_HARMONIC_NOTCH_FILTERS; i++) { for (auto &notch : ins.harmonic_notches) {
if (ins.gyro_harmonic_notch_enabled(i) && if (notch.params.enabled() &&
ins.get_gyro_harmonic_notch_tracking_mode(i) != HarmonicNotchDynamicMode::Fixed) { notch.params.tracking_mode() != HarmonicNotchDynamicMode::Fixed) {
state.rate_rpm = ins.get_gyro_dynamic_notch_center_freq_hz(i) * 60.0f; state.rate_rpm = notch.params.center_freq_hz() * 60;
state.rate_rpm *= ap_rpm._params[state.instance].scaling; state.rate_rpm *= ap_rpm._params[state.instance].scaling;
state.signal_quality = 0.5f; state.signal_quality = 0.5f;
state.last_reading_ms = AP_HAL::millis(); state.last_reading_ms = AP_HAL::millis();