Browse Source

Copter: re-enable CPU failsafe if arming fails

mission-4.1.18
Randy Mackay 10 years ago
parent
commit
beb54b087b
  1. 1
      ArduCopter/motors.pde

1
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()) { 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")); gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Gyro cal failed"));
AP_Notify::flags.armed = false; AP_Notify::flags.armed = false;
failsafe_enable();
return false; return false;
} }
did_ground_start = true; did_ground_start = true;

Loading…
Cancel
Save