mirror of https://github.com/ArduPilot/ardupilot
Plane: when ICE overrides throttle zero the vfwd integrator
This commit is contained in:
parent
ef473a4372
commit
49255d3315
|
@ -909,6 +909,9 @@ void Plane::set_servos(void)
|
||||||
if (g2.ice_control.throttle_override(override_pct)) {
|
if (g2.ice_control.throttle_override(override_pct)) {
|
||||||
// the ICE controller wants to override the throttle for starting
|
// the ICE controller wants to override the throttle for starting
|
||||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, override_pct);
|
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
|
// run output mixer and send values to the hal for output
|
||||||
|
|
Loading…
Reference in New Issue