Browse Source

Plane: when ICE overrides throttle zero the vfwd integrator

apm_2208
Andrew Tridgell 3 years ago
parent
commit
6a1e80a03a
  1. 3
      ArduPlane/servos.cpp

3
ArduPlane/servos.cpp

@ -915,6 +915,9 @@ void Plane::set_servos(void) @@ -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

Loading…
Cancel
Save