mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: ahrs pre-arm skips position checks
This commit is contained in:
parent
f6da769de8
commit
e7c2eb1705
@ -66,7 +66,7 @@ bool AP_Arming_Sub::ins_checks(bool display_failure)
|
|||||||
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
||||||
(checks_to_perform & ARMING_CHECK_INS)) {
|
(checks_to_perform & ARMING_CHECK_INS)) {
|
||||||
char failure_msg[50] = {};
|
char failure_msg[50] = {};
|
||||||
if (!AP::ahrs().pre_arm_check(failure_msg, sizeof(failure_msg))) {
|
if (!AP::ahrs().pre_arm_check(false, failure_msg, sizeof(failure_msg))) {
|
||||||
check_failed(ARMING_CHECK_INS, display_failure, "AHRS: %s", failure_msg);
|
check_failed(ARMING_CHECK_INS, display_failure, "AHRS: %s", failure_msg);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user