mirror of https://github.com/ArduPilot/ardupilot
Plane: ahrs pre-arm always runs position checks
This commit is contained in:
parent
e7c2eb1705
commit
d487d6152e
|
@ -125,7 +125,7 @@ bool AP_Arming_Plane::ins_checks(bool display_failure)
|
|||
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
||||
(checks_to_perform & ARMING_CHECK_INS)) {
|
||||
char failure_msg[50] = {};
|
||||
if (!AP::ahrs().pre_arm_check(failure_msg, sizeof(failure_msg))) {
|
||||
if (!AP::ahrs().pre_arm_check(true, failure_msg, sizeof(failure_msg))) {
|
||||
check_failed(ARMING_CHECK_INS, display_failure, "AHRS: %s", failure_msg);
|
||||
return false;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue