From 28cf9d2f24c974daa159bdcfcf337957e8aac164 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 2 Feb 2019 21:13:35 +1100 Subject: [PATCH] Plane: allow rudder at zero throttle if rudder disarming is disabled --- ArduPlane/quadplane.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index f8072d7986..34d6775937 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1064,7 +1064,8 @@ void QuadPlane::control_loiter() */ float QuadPlane::get_pilot_input_yaw_rate_cds(void) const { - if (plane.get_throttle_input() <= 0 && !plane.auto_throttle_mode) { + if (plane.get_throttle_input() <= 0 && !plane.auto_throttle_mode && + plane.arming.get_rudder_arming_type() != AP_Arming::ARMING_RUDDER_DISABLED) { // the user may be trying to disarm return 0; }