From eeaf135cca210e9deb9a639bceabe6247306a48c Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Tue, 11 Aug 2020 14:04:10 +0900
Subject: [PATCH] AP_Arming: integrate ahrs.pre_arm_check

---
 ArduCopter/AP_Arming.cpp | 11 ++++-------
 ArduPlane/AP_Arming.cpp  |  9 +++------
 2 files changed, 7 insertions(+), 13 deletions(-)

diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp
index 4f19e6b4d1..313d84ee70 100644
--- a/ArduCopter/AP_Arming.cpp
+++ b/ArduCopter/AP_Arming.cpp
@@ -509,12 +509,9 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
 {
     // always check if inertial nav has started and is ready
     const AP_AHRS_NavEKF &ahrs = AP::ahrs_navekf();
-    if (!ahrs.prearm_healthy()) {
-        const char *reason = ahrs.prearm_failure_reason();
-        if (reason == nullptr) {
-            reason = "AHRS not healthy";
-        }
-        check_failed(display_failure, "%s", reason);
+    char failure_msg[50] = {};
+    if (!ahrs.pre_arm_check(failure_msg, sizeof(failure_msg))) {
+        check_failed(display_failure, "%s", failure_msg);
         return false;
     }
 
@@ -530,7 +527,7 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
 
     if (mode_requires_gps) {
         if (!copter.position_ok()) {
-            // There is no need to call prearm_failure_reason again, because prearm_healthy sure be true if we reach here
+            // vehicle level position estimate checks
             check_failed(display_failure, "Need Position Estimate");
             return false;
         }
diff --git a/ArduPlane/AP_Arming.cpp b/ArduPlane/AP_Arming.cpp
index 054398f97b..7adc4adfae 100644
--- a/ArduPlane/AP_Arming.cpp
+++ b/ArduPlane/AP_Arming.cpp
@@ -124,12 +124,9 @@ bool AP_Arming_Plane::ins_checks(bool display_failure)
     // additional plane specific checks
     if ((checks_to_perform & ARMING_CHECK_ALL) ||
         (checks_to_perform & ARMING_CHECK_INS)) {
-        if (!AP::ahrs().prearm_healthy()) {
-            const char *reason = AP::ahrs().prearm_failure_reason();
-            if (reason == nullptr) {
-                reason = "AHRS not healthy";
-            }
-            check_failed(ARMING_CHECK_INS, display_failure, "%s", reason);
+        char failure_msg[50] = {};
+        if (!AP::ahrs().pre_arm_check(failure_msg, sizeof(failure_msg))) {
+            check_failed(ARMING_CHECK_INS, display_failure, "%s", failure_msg);
             return false;
         }
     }