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;