AP_GyroFFT: pass GyroFFT loop rate in Hz rather than period in us

It just calculates this anyway

Also stops assigning a uint16_t value into a uint32_t value
This commit is contained in:
Peter Barker 2021-06-07 16:13:14 +10:00 committed by Andrew Tridgell
parent e5888d42d9
commit 9ea9c15c6a
2 changed files with 2 additions and 3 deletions

View File

@ -180,7 +180,7 @@ AP_GyroFFT::AP_GyroFFT()
}
// initialize the FFT parameters and engine
void AP_GyroFFT::init(uint32_t target_looptime_us)
void AP_GyroFFT::init(uint16_t loop_rate_hz)
{
// if FFT analysis is not enabled we don't want to allocate any of the associated resources
if (!_enable) {
@ -226,7 +226,6 @@ void AP_GyroFFT::init(uint32_t target_looptime_us)
if (_sample_mode == 0) {
_fft_sampling_rate_hz = _ins->get_raw_gyro_rate_hz();
} else {
const uint16_t loop_rate_hz = 1000*1000UL / target_looptime_us;
_fft_sampling_rate_hz = loop_rate_hz / _sample_mode;
for (uint8_t axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
if (!_downsampled_gyro_data[axis].set_size(_window_size + _samples_per_frame)) {

View File

@ -47,7 +47,7 @@ public:
AP_GyroFFT(const AP_GyroFFT &other) = delete;
AP_GyroFFT &operator=(const AP_GyroFFT&) = delete;
void init(uint32_t target_looptime);
void init(uint16_t loop_rate_hz);
// cycle through the FFT steps - runs in the FFT thread
uint16_t run_cycle();