mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: dynamic notch setting via FFT
This commit is contained in:
parent
0e9b2a26c5
commit
3832bc455d
@ -491,6 +491,12 @@ void Plane::update_dynamic_notch()
|
|||||||
case HarmonicNotchDynamicMode::UpdateBLHeli: // BLHeli based tracking
|
case HarmonicNotchDynamicMode::UpdateBLHeli: // BLHeli based tracking
|
||||||
ins.update_harmonic_notch_freq_hz(MAX(ref_freq, AP_BLHeli::get_singleton()->get_average_motor_frequency_hz() * ref));
|
ins.update_harmonic_notch_freq_hz(MAX(ref_freq, AP_BLHeli::get_singleton()->get_average_motor_frequency_hz() * ref));
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
|
#if HAL_GYROFFT_ENABLED
|
||||||
|
case HarmonicNotchDynamicMode::UpdateGyroFFT: // FFT based tracking
|
||||||
|
// set the harmonic notch filter frequency scaled on measured frequency
|
||||||
|
ins.update_harmonic_notch_freq_hz(gyro_fft.get_weighted_noise_center_freq_hz());
|
||||||
|
break;
|
||||||
#endif
|
#endif
|
||||||
case HarmonicNotchDynamicMode::Fixed: // static
|
case HarmonicNotchDynamicMode::Fixed: // static
|
||||||
default:
|
default:
|
||||||
|
Loading…
Reference in New Issue
Block a user