From 959c0eccfd05170041984b53ed2f9a501a8e6335 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 19 Dec 2015 14:59:44 +0900 Subject: [PATCH] Copter: reject changing to throw mode while armed --- ArduCopter/control_throw.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/ArduCopter/control_throw.cpp b/ArduCopter/control_throw.cpp index 609109c44e..d38802c0c9 100644 --- a/ArduCopter/control_throw.cpp +++ b/ArduCopter/control_throw.cpp @@ -10,6 +10,12 @@ bool Copter::throw_init(bool ignore_checks) // do not allow helis to use throw to start return false; #endif + + // do not enter the mode when already armed + if (motors.armed()) { + return false; + } + // this mode needs a position reference if (position_ok()) { return true;