autotest: Rover: ensure we actually stop at rally point

This commit is contained in:
Peter Barker 2022-08-13 12:21:48 +10:00 committed by Peter Barker
parent a237a42390
commit add5243634

View File

@ -1239,11 +1239,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
if ex is not None: if ex is not None:
raise ex raise ex
def test_rally_points(self): def Rally(self):
self.reboot_sitl() # to ensure starting point is as expected
self.load_rally("rover-test-rally.txt") self.load_rally("rover-test-rally.txt")
accuracy = self.get_parameter("WP_RADIUS")
self.wait_ready_to_arm() self.wait_ready_to_arm()
self.arm_vehicle() self.arm_vehicle()
@ -1257,7 +1254,8 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
-105.229401, -105.229401,
0, 0,
0) 0)
self.wait_location(loc, accuracy=accuracy) accuracy = self.get_parameter("WP_RADIUS")
self.wait_location(loc, accuracy=accuracy, minimum_duration=10)
self.disarm_vehicle() self.disarm_vehicle()
def fence_with_bad_frame(self, target_system=1, target_component=1): def fence_with_bad_frame(self, target_system=1, target_component=1):
@ -6070,7 +6068,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
("Rally", ("Rally",
"Test Rally Points", "Test Rally Points",
self.test_rally_points), self.Rally),
("Offboard", ("Offboard",
"Test Offboard Control", "Test Offboard Control",