Plane: Change throttle_override to pass in current throttle value

This commit is contained in:
TunaLobster 2022-05-19 20:39:50 -05:00 committed by Tom Pittenger
parent 9e26556408
commit df0a75a0bb
1 changed files with 1 additions and 1 deletions

View File

@ -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);