From 86d2ccf0e7dd1b7ba38540b77f845dc03a204956 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 9 May 2022 15:46:41 +1000 Subject: [PATCH] Plane: update gyro fft throttle allows for updating or learned FFT freq --- ArduPlane/quadplane.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index d370fcdc37..3f9a862920 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1870,6 +1870,9 @@ void QuadPlane::update_throttle_hover() ahrs.airspeed_estimate(aspeed) && aspeed < plane.aparm.airspeed_min*0.3) { // Can we set the time constant automatically motors->update_throttle_hover(0.01f); +#if HAL_GYROFFT_ENABLED + plane.gyro_fft.update_freq_hover(0.01f, motors->get_throttle_out()); +#endif } } /*