From 7db94286e9510b37904b9975e50f59eb91ffe780 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 3 Feb 2025 14:35:48 +1100 Subject: [PATCH] Tools: add option to require position for Rover before arming --- Tools/autotest/rover.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) 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