mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: add arming message for compass not detected but assigned
This commit is contained in:
parent
25b0a113d5
commit
b203badfb3
|
@ -92,8 +92,9 @@ bool AP_Arming_Copter::compass_checks(bool display_failure)
|
|||
if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_COMPASS)) {
|
||||
// check compass offsets have been set. AP_Arming only checks
|
||||
// this if learning is off; Copter *always* checks.
|
||||
if (!AP::compass().configured()) {
|
||||
check_failed(ARMING_CHECK_COMPASS, display_failure, "Compass not calibrated");
|
||||
char failure_msg[50] = {};
|
||||
if (!AP::compass().configured(failure_msg, ARRAY_SIZE(failure_msg))) {
|
||||
check_failed(ARMING_CHECK_COMPASS, display_failure, "%s", failure_msg);
|
||||
ret = false;
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue