Skip to content

Commit

Permalink
ArduPlane: option to keep landing throttle at thr_min during flare an…
Browse files Browse the repository at this point in the history
…d touchdown, not zero.
  • Loading branch information
davidbuzz committed May 18, 2020
1 parent 0af3fb4 commit 4ceee26
Showing 1 changed file with 5 additions and 2 deletions.
7 changes: 5 additions & 2 deletions ArduPlane/servos.cpp
Expand Up @@ -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));
Expand Down

0 comments on commit 4ceee26

Please sign in to comment.