|
|
|
@ -469,8 +469,11 @@ void Plane::set_servos_controlled(void)
@@ -469,8 +469,11 @@ void Plane::set_servos_controlled(void)
|
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, 0); |
|
|
|
|
} |
|
|
|
|
} else if (suppress_throttle()) { |
|
|
|
|
// throttle is suppressed in auto mode
|
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0); |
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0 ); // default
|
|
|
|
|
// throttle is suppressed (above) to zero in final flare in auto mode, but we allow instead thr_min if user prefers, eg turbines:
|
|
|
|
|
if (landing.is_flaring() && landing.use_thr_min_during_flare() ) { |
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, aparm.throttle_min.get()); |
|
|
|
|
} |
|
|
|
|
if (g.throttle_suppress_manual) { |
|
|
|
|
// manual pass through of throttle while throttle is suppressed
|
|
|
|
|
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, get_throttle_input(true)); |
|
|
|
|