mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Arming: add arming message for compass not detected but assigned
This commit is contained in:
parent
1b63cb6d5c
commit
de86342e93
@ -396,10 +396,13 @@ bool AP_Arming::compass_checks(bool report)
|
||||
return false;
|
||||
}
|
||||
// check compass learning is on or offsets have been set
|
||||
if (!_compass.learn_offsets_enabled() && !_compass.configured()) {
|
||||
check_failed(ARMING_CHECK_COMPASS, report, "Compass not calibrated");
|
||||
if (!_compass.learn_offsets_enabled()) {
|
||||
char failure_msg[50] = {};
|
||||
if (!_compass.configured(failure_msg, ARRAY_SIZE(failure_msg))) {
|
||||
check_failed(ARMING_CHECK_COMPASS, report, "%s", failure_msg);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// check for unreasonable compass offsets
|
||||
const Vector3f offsets = _compass.get_offsets();
|
||||
|
Loading…
Reference in New Issue
Block a user