diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index f20135d9ef..dcdd996439 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -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)); diff --git a/libraries/AP_Landing/AP_Landing.cpp b/libraries/AP_Landing/AP_Landing.cpp index 007f3086c5..c795a44c9f 100644 --- a/libraries/AP_Landing/AP_Landing.cpp +++ b/libraries/AP_Landing/AP_Landing.cpp @@ -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