From 49255d3315b0d1226408d8151a431dfc88e36fe1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 5 Jul 2022 16:13:12 +1000 Subject: [PATCH] Plane: when ICE overrides throttle zero the vfwd integrator --- ArduPlane/servos.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 7e9c49b7f8..1ec3687bc8 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -909,6 +909,9 @@ void Plane::set_servos(void) if (g2.ice_control.throttle_override(override_pct)) { // the ICE controller wants to override the throttle for starting SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, override_pct); +#if HAL_QUADPLANE_ENABLED + quadplane.vel_forward.integrator = 0; +#endif } // run output mixer and send values to the hal for output