AP_GyroFFT: move to new constant dt low pass filter class

This commit is contained in:
Iampete1 2024-07-27 13:12:50 +01:00 committed by Andrew Tridgell
parent 5cc63d7e6f
commit 1d589c5244
1 changed files with 2 additions and 2 deletions

View File

@ -157,7 +157,7 @@ private:
}
private:
LowPassFilterFloat _lowpass_filter[XYZ_AXIS_COUNT];
LowPassFilterConstDtFloat _lowpass_filter[XYZ_AXIS_COUNT];
FilterWithBuffer<float,3> _median_filter[XYZ_AXIS_COUNT];
};
@ -311,7 +311,7 @@ private:
// smoothing filter on the bandwidth
MedianLowPassFilter3dFloat _center_bandwidth_filter[FrequencyPeak::MAX_TRACKED_PEAKS];
// smoothing filter on the frequency fit
LowPassFilterFloat _harmonic_fit_filter[XYZ_AXIS_COUNT];
LowPassFilterConstDtFloat _harmonic_fit_filter[XYZ_AXIS_COUNT];
// configured sampling rate
uint16_t _fft_sampling_rate_hz;