mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RPM: use HarmonicNotch class
This commit is contained in:
parent
86db91e3b4
commit
e6b56ce9ba
@ -32,10 +32,10 @@ AP_RPM_HarmonicNotch::AP_RPM_HarmonicNotch(AP_RPM &_ap_rpm, uint8_t _instance, A
|
||||
void AP_RPM_HarmonicNotch::update(void)
|
||||
{
|
||||
AP_InertialSensor& ins = AP::ins();
|
||||
for (uint8_t i=0; i<HAL_INS_NUM_HARMONIC_NOTCH_FILTERS; i++) {
|
||||
if (ins.gyro_harmonic_notch_enabled(i) &&
|
||||
ins.get_gyro_harmonic_notch_tracking_mode(i) != HarmonicNotchDynamicMode::Fixed) {
|
||||
state.rate_rpm = ins.get_gyro_dynamic_notch_center_freq_hz(i) * 60.0f;
|
||||
for (auto ¬ch : ins.harmonic_notches) {
|
||||
if (notch.params.enabled() &&
|
||||
notch.params.tracking_mode() != HarmonicNotchDynamicMode::Fixed) {
|
||||
state.rate_rpm = notch.params.center_freq_hz() * 60;
|
||||
state.rate_rpm *= ap_rpm._params[state.instance].scaling;
|
||||
state.signal_quality = 0.5f;
|
||||
state.last_reading_ms = AP_HAL::millis();
|
||||
|
Loading…
Reference in New Issue
Block a user