diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde
index 9e736b0052d7d0531d3559cd7e56099c4f74e88b..80217627f9f5855e6d41db9ccc08c607f191cf3d 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;
     }