diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 9c4dee7f22..fa8cc8aab0 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -603,7 +603,7 @@ bool AP_Arming::gps_checks(bool report) // Any failure messages from GPS backends char failure_msg[50] = {}; - if (!AP::gps().backends_healthy(failure_msg, ARRAY_SIZE(failure_msg))) { + if (!AP::gps().pre_arm_checks(failure_msg, ARRAY_SIZE(failure_msg))) { if (failure_msg[0] != '\0') { check_failed(ARMING_CHECK_GPS, report, "%s", failure_msg); }