mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Vehicle: dynamic notch use min ratio for RPM tracking
This commit is contained in:
parent
a3f43b26ae
commit
f5d6e167b5
@ -656,7 +656,7 @@ void AP_Vehicle::update_dynamic_notch(AP_InertialSensor::HarmonicNotch ¬ch)
|
|||||||
float rpm;
|
float rpm;
|
||||||
if (rpm_sensor != nullptr && rpm_sensor->get_rpm(sensor, rpm)) {
|
if (rpm_sensor != nullptr && rpm_sensor->get_rpm(sensor, rpm)) {
|
||||||
// set the harmonic notch filter frequency from the main rotor rpm
|
// set the harmonic notch filter frequency from the main rotor rpm
|
||||||
notch.update_freq_hz(MAX(ref_freq, rpm * ref * (1.0/60)));
|
notch.update_freq_hz(MAX(ref_freq * notch.params.freq_min_ratio(), rpm * ref * (1.0/60)));
|
||||||
} else {
|
} else {
|
||||||
notch.update_freq_hz(ref_freq);
|
notch.update_freq_hz(ref_freq);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user