diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 1a61059964..0ae928a6e0 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1793,8 +1793,17 @@ void QuadPlane::update_throttle_suppression(void) return; } - // if the users throttle is above zero then allow motors to run - if (!is_zero(plane.get_throttle_input())) { + /* if the users throttle is above zero then allow motors to run + + if the user has unset the "check throttle zero when arming" + then the RC controller has a sprung throttle and we should not + consider non-zero throttle to mean that pilot is commanding + takeoff unless in a manual thottle mode + */ + if (!is_zero(plane.get_throttle_input()) && + (rc().arming_check_throttle() || + plane.control_mode->is_vtol_man_throttle() || + plane.channel_throttle->norm_input_dz() > 0)) { return; }