From 5135a11fbca9340b4f9af56b49204534cc0005fd Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 1 Dec 2016 10:24:53 +0900 Subject: [PATCH] Copter: protect against arming while already armed Previously it was possible to arm the vehicle (from the GCS) even thought the vehicle was already armed which would lead to the motors stopping for 2 seconds --- ArduCopter/motors.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ArduCopter/motors.cpp b/ArduCopter/motors.cpp index 5025c3bcb8..80f82914bd 100644 --- a/ArduCopter/motors.cpp +++ b/ArduCopter/motors.cpp @@ -130,6 +130,11 @@ bool Copter::init_arm_motors(bool arming_from_gcs) } in_arm_motors = true; + // return true if already armed + if (motors.armed()) { + return true; + } + // run pre-arm-checks and display failures if (!all_arming_checks_passing(arming_from_gcs)) { AP_Notify::events.arming_failed = true;