mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_RPM: fix reporting of RPM from the harmonic notch
This commit is contained in:
parent
81c138e0a4
commit
9d3f4d1906
@ -35,7 +35,7 @@ void AP_RPM_HarmonicNotch::update(void)
|
|||||||
for (auto ¬ch : ins.harmonic_notches) {
|
for (auto ¬ch : ins.harmonic_notches) {
|
||||||
if (notch.params.enabled() &&
|
if (notch.params.enabled() &&
|
||||||
notch.params.tracking_mode() != HarmonicNotchDynamicMode::Fixed) {
|
notch.params.tracking_mode() != HarmonicNotchDynamicMode::Fixed) {
|
||||||
state.rate_rpm = notch.params.center_freq_hz() * 60;
|
state.rate_rpm = notch.calculated_notch_freq_hz[0] * 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();
|
||||||
|
Loading…
Reference in New Issue
Block a user