AP_Vehicle: pass GyroFFT loop rate in Hz rather than period in us
It just calculates this anyway
This commit is contained in:
parent
9ea9c15c6a
commit
295276cd37
@ -152,7 +152,7 @@ void AP_Vehicle::setup()
|
||||
|
||||
// gyro FFT needs to be initialized really late
|
||||
#if HAL_GYROFFT_ENABLED
|
||||
gyro_fft.init(AP::scheduler().get_loop_period_us());
|
||||
gyro_fft.init(AP::scheduler().get_loop_rate_hz());
|
||||
#endif
|
||||
#if HAL_RUNCAM_ENABLED
|
||||
runcam.init();
|
||||
|
Loading…
Reference in New Issue
Block a user