From beb54b087bd7740adefd813501f42b026336a70b Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 29 Oct 2014 15:59:22 +0900 Subject: [PATCH] Copter: re-enable CPU failsafe if arming fails --- ArduCopter/motors.pde | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index 446659e24f..11c5084443 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -149,6 +149,7 @@ 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;