mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Copter: add compass health to arming check
This commit is contained in:
parent
b9dcf1108d
commit
bf0e7fb3a9
@ -656,6 +656,14 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||||||
return false;
|
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 (compass.is_calibrating()) {
|
||||||
if (display_failure) {
|
if (display_failure) {
|
||||||
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Compass calibration running");
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Compass calibration running");
|
||||||
|
Loading…
Reference in New Issue
Block a user