From 742cdf6b13a7cfa7e39c24a035b68d7d369582b8 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 11 Jan 2017 21:38:22 +0900 Subject: [PATCH] Copter: fix arming while armed bug If a mavlink command was sent to arm the vehicle while it was already armed, the in_arm_motors boolean was left as true meaning the vehicle could never be armed again using a mavlink message. This resolves issue #5546. --- ArduCopter/motors.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduCopter/motors.cpp b/ArduCopter/motors.cpp index 80f82914bd..1ea260ee8d 100644 --- a/ArduCopter/motors.cpp +++ b/ArduCopter/motors.cpp @@ -132,6 +132,7 @@ bool Copter::init_arm_motors(bool arming_from_gcs) // return true if already armed if (motors.armed()) { + in_arm_motors = false; return true; }