mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Plane: when ICE overrides throttle zero the vfwd integrator
This commit is contained in:
parent
32e1767647
commit
6a1e80a03a
@ -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…
Reference in New Issue
Block a user