mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Arming: Compass calibration running is a pre arm failure, rather then an arming failure
This commit is contained in:
parent
ded1bad6c3
commit
126296b61d
@ -295,7 +295,7 @@ bool AP_Arming::compass_checks(bool report)
|
||||
//check if compass is calibrating
|
||||
if (_compass.is_calibrating()) {
|
||||
if (report) {
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "Arm: Compass calibration running");
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Compass calibration running");
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user