From 683f3a55c40a790bf03360e1e3de76adb3d93415 Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Wed, 29 Oct 2014 15:59:22 +0900
Subject: [PATCH] Copter: re-enable CPU failsafe if arming fails

---
 ArduCopter/motors.pde | 3 ++-
 1 file changed, 2 insertions(+), 1 deletion(-)

diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde
index 9e736b005..80217627f 100644
--- a/ArduCopter/motors.pde
+++ b/ArduCopter/motors.pde
@@ -177,8 +177,9 @@ static bool init_arm_motors()
         if (((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) && !ins.gyro_calibrated_ok_all()) {
             gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Gyro cal failed"));
             AP_Notify::flags.armed = false;
+            failsafe_enable();
             return false;
-    }
+        }
         did_ground_start = true;
     }
 
-- 
GitLab