mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: option to keep landing throttle at thr_min during flare and touchdown, not zero.
This commit is contained in:
parent
dc3db0476b
commit
d4df145b4b
|
@ -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));
|
||||
|
|
|
@ -143,7 +143,7 @@ const AP_Param::GroupInfo AP_Landing::var_info[] = {
|
|||
// @Path: AP_Landing_Deepstall.cpp
|
||||
AP_SUBGROUPINFO(deepstall, "DS_", 15, AP_Landing, AP_Landing_Deepstall),
|
||||
|
||||
// @Param: _OPTIONS
|
||||
// @Param: OPTIONS
|
||||
// @DisplayName: Landing options bitmask
|
||||
// @Description: Bitmask of options to use with landing.
|
||||
// @Bitmask: 0: honor min throttle during landing flare
|
||||
|
|
Loading…
Reference in New Issue