Browse Source

Plane: update gyro fft throttle

allows for updating or learned FFT freq
apm_2208
Andrew Tridgell 3 years ago
parent
commit
86d2ccf0e7
  1. 3
      ArduPlane/quadplane.cpp

3
ArduPlane/quadplane.cpp

@ -1870,6 +1870,9 @@ void QuadPlane::update_throttle_hover() @@ -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
}
}
/*

Loading…
Cancel
Save