From 81e453dee3e456ebcb34da7bfd78d6a9b5a16ea3 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Thu, 10 May 2018 21:03:06 -0700 Subject: [PATCH] AP_Arming: Restrict GPS/AHRS difference to a 2D solution --- libraries/AP_Arming/AP_Arming.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 27cb5c7e37..bb92bb34a4 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -384,7 +384,7 @@ bool AP_Arming::gps_checks(bool report) Location gps_loc = gps.location(); Location ahrs_loc; if (ahrs.get_position(ahrs_loc)) { - float distance = location_3d_diff_NED(gps_loc, ahrs_loc).length(); + const float distance = location_diff(gps_loc, ahrs_loc).length(); if (distance > AP_ARMING_AHRS_GPS_ERROR_MAX) { if (report) { gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: GPS and AHRS differ by %4.1fm", (double)distance);