mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Copter: add compass health to arming check
This commit is contained in:
parent
9dd4755084
commit
df8cc895b3
@ -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…
Reference in New Issue
Block a user