Browse Source

Copter: add compass health to arming check

master
Randy Mackay 8 years ago
parent
commit
bf0e7fb3a9
  1. 8
      ArduCopter/arming_checks.cpp

8
ArduCopter/arming_checks.cpp

@ -656,6 +656,14 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs) @@ -656,6 +656,14 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
return false;
}
// check compass health
if (!compass.healthy()) {
if (display_failure) {
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Compass not healthy");
}
return false;
}
if (compass.is_calibrating()) {
if (display_failure) {
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Compass calibration running");

Loading…
Cancel
Save