mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: Change throttle_override to pass in current throttle value
This commit is contained in:
parent
9e26556408
commit
df0a75a0bb
@ -911,7 +911,7 @@ void Plane::set_servos(void)
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t override_pct;
|
||||
float override_pct = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle);
|
||||
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);
|
||||
|
Loading…
Reference in New Issue
Block a user