Plane: ahrs pre-arm always runs position checks

This commit is contained in:
Randy Mackay 2021-01-21 15:24:01 +09:00 committed by Andrew Tridgell
parent e7c2eb1705
commit d487d6152e

View File

@ -125,7 +125,7 @@ bool AP_Arming_Plane::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(true, 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;
} }