mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: convert to new get_rpm() API
This commit is contained in:
parent
375c08f39c
commit
8aaefea2a4
@ -466,9 +466,10 @@ void Plane::update_dynamic_notch()
|
||||
break;
|
||||
|
||||
case HarmonicNotchDynamicMode::UpdateRPM: // rpm sensor based tracking
|
||||
if (rpm_sensor.healthy(0)) {
|
||||
float rpm;
|
||||
if (rpm_sensor.get_rpm(0, rpm)) {
|
||||
// set the harmonic notch filter frequency from the main rotor rpm
|
||||
ins.update_harmonic_notch_freq_hz(MAX(ref_freq, rpm_sensor.get_rpm(0) * ref / 60.0f));
|
||||
ins.update_harmonic_notch_freq_hz(MAX(ref_freq, rpm * ref / 60.0f));
|
||||
} else {
|
||||
ins.update_harmonic_notch_freq_hz(ref_freq);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user