From 694801254f4c3bbd4f229faea464e45ad6c50112 Mon Sep 17 00:00:00 2001 From: Siddharth Purohit Date: Wed, 3 Mar 2021 15:03:12 +0530 Subject: [PATCH] Rover: do common gps arming checks first before moving on --- Rover/AP_Arming.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/Rover/AP_Arming.cpp b/Rover/AP_Arming.cpp index e444ac11a6..e66caede92 100644 --- a/Rover/AP_Arming.cpp +++ b/Rover/AP_Arming.cpp @@ -39,6 +39,11 @@ bool AP_Arming_Rover::gps_checks(bool display_failure) return true; } + // call parent gps checks + if (!AP_Arming::gps_checks(display_failure)) { + return false; + } + const AP_AHRS &ahrs = AP::ahrs(); // always check if inertial nav has started and is ready @@ -61,8 +66,7 @@ bool AP_Arming_Rover::gps_checks(bool display_failure) return false; } - // call parent gps checks - return AP_Arming::gps_checks(display_failure); + return true; } bool AP_Arming_Rover::pre_arm_checks(bool report)