From 386318399628fa5a5b9c964d4b6a7d3e41000e38 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 10 Apr 2023 12:28:05 +1000 Subject: [PATCH] autotest: give Rover longer to arrive home vagaries of interaction with Python script means we need to give this more time when running balancebot --- Tools/autotest/rover.py | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 86bd82c546..64e83424f1 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -1295,17 +1295,21 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) self.wait_ready_to_arm() self.arm_vehicle() + # calculate early to avoid round-trips while vehicle is moving: + accuracy = self.get_parameter("WP_RADIUS") + self.reach_heading_manual(10) self.reach_distance_manual(50) self.change_mode("RTL") + # location copied in from rover-test-rally.txt: loc = mavutil.location(40.071553, -105.229401, 0, 0) - accuracy = self.get_parameter("WP_RADIUS") - self.wait_location(loc, accuracy=accuracy, minimum_duration=10) + + self.wait_location(loc, accuracy=accuracy, minimum_duration=10, timeout=45) self.disarm_vehicle() def fence_with_bad_frame(self, target_system=1, target_component=1):