From f5a15fb7c5baa474027ca4eac4744d38255e719b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 2 Jan 2016 15:16:31 +1100 Subject: [PATCH] Plane: don't yaw quad when disarming --- ArduPlane/quadplane.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index f010b7f1c3..1b580a538f 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -546,6 +546,10 @@ float QuadPlane::get_pilot_desired_yaw_rate_cds(void) // use bank angle to get desired yaw rate return desired_yaw_rate_cds(); } + if (plane.channel_throttle->control_in <= 0) { + // the user may be trying to disarm + return 0; + } const float yaw_rate_max_dps = 100; return plane.channel_rudder->norm_input() * 100 * yaw_rate_max_dps; }