mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: allow for throttle control in MANUAL when disarmed
pass base throttle down to ICE subsystem to allow for throttle when disarmed in MANUAL
This commit is contained in:
parent
431fbacb2c
commit
4e141fc67f
@ -880,6 +880,8 @@ void Plane::set_servos(void)
|
||||
// slew rate limit throttle
|
||||
throttle_slew_limit(SRV_Channel::k_throttle);
|
||||
|
||||
const float base_throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle);
|
||||
|
||||
if (!arming.is_armed()) {
|
||||
//Some ESCs get noisy (beep error msgs) if PWM == 0.
|
||||
//This little segment aims to avoid this.
|
||||
@ -905,9 +907,9 @@ void Plane::set_servos(void)
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t override_pct;
|
||||
if (g2.ice_control.throttle_override(override_pct)) {
|
||||
// the ICE controller wants to override the throttle for starting
|
||||
float override_pct = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle);
|
||||
if (g2.ice_control.throttle_override(override_pct, base_throttle)) {
|
||||
// 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;
|
||||
|
Loading…
Reference in New Issue
Block a user