From 6a1e80a03af8a22651f3b142091a949865cf7650 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 5c3a0c8354..176dd0169c 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -915,6 +915,9 @@ void Plane::set_servos(void) if (g2.ice_control.throttle_override(override_pct)) { // the ICE controller wants to override the throttle for starting, idle, or redline 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