diff --git a/Rover/AP_Arming_Rover.cpp b/Rover/AP_Arming_Rover.cpp index 80534e3a93484..8cdf9555d45f3 100644 --- a/Rover/AP_Arming_Rover.cpp +++ b/Rover/AP_Arming_Rover.cpp @@ -34,7 +34,9 @@ bool AP_Arming_Rover::rc_calibration_checks(const bool display_failure) // performs pre_arm gps related checks and returns true if passed bool AP_Arming_Rover::gps_checks(bool display_failure) { - if (!rover.control_mode->requires_position() && !rover.control_mode->requires_velocity()) { + if (!require_location && + !rover.control_mode->requires_position() && + !rover.control_mode->requires_velocity()) { // we don't care! return true; } diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 3a401eb0b4809..fef6519a7dd82 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -6947,7 +6947,7 @@ def SDPolyFence(self): self.delay_sim_time(1000) - def REQUIRE_POSITION_FOR_ARMING(self): + def REQUIRE_LOCATION_FOR_ARMING(self): '''check DriveOption::REQUIRE_POSITION_FOR_ARMING works''' self.context_push() self.set_parameters({ @@ -6966,7 +6966,7 @@ def REQUIRE_POSITION_FOR_ARMING(self): self.change_mode('MANUAL') self.set_parameters({ - "DRIVE_OPTIONS": 1, + "ARMING_NEED_LOC": 1, }) self.assert_prearm_failure("waiting for home", other_prearm_failures_fatal=False) self.context_pop() @@ -7070,7 +7070,7 @@ def tests(self): self.ClearMission, self.JammingSimulation, self.BatteryInvalid, - self.REQUIRE_POSITION_FOR_ARMING, + self.REQUIRE_LOCATION_FOR_ARMING, ]) return ret diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index d08612bfcfd7d..6790e57593bae 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -89,7 +89,7 @@ // whether the parameter should be shown: #ifndef AP_ARMING_NEED_LOC_PARAMETER_ENABLED // determine whether ARMING_NEED_POS is shown: -#if APM_BUILD_COPTER_OR_HELI +#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_Rover) #define AP_ARMING_NEED_LOC_PARAMETER_ENABLED 1 #else #define AP_ARMING_NEED_LOC_PARAMETER_ENABLED 0 @@ -98,7 +98,7 @@ // if ARMING_NEED_POS is shown, determine what its default should be: #if AP_ARMING_NEED_LOC_PARAMETER_ENABLED -#if APM_BUILD_COPTER_OR_HELI +#if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_Rover) #define AP_ARMING_NEED_LOC_DEFAULT 0 #else #error "Unable to find value for AP_ARMING_NEED_LOC_DEFAULT"