Browse Source

Tools: autotest: get accuracy before doing RTL

It can take a very long time to get our parameter value, so get it while
we're NOT moving away from the RTL location!
master
Peter Barker 6 years ago committed by Peter Barker
parent
commit
844999c458
  1. 6
      Tools/autotest/apmrover2.py
  2. 2
      Tools/autotest/common.py

6
Tools/autotest/apmrover2.py

@ -923,10 +923,14 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
raise ex raise ex
def test_rally_points(self): def test_rally_points(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()
self.reach_heading_manual(10) self.reach_heading_manual(10)
self.reach_distance_manual(50) self.reach_distance_manual(50)
@ -936,7 +940,7 @@ 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=self.get_parameter("WP_RADIUS")) self.wait_location(loc, accuracy=accuracy)
self.disarm_vehicle() self.disarm_vehicle()
def tests(self): def tests(self):

2
Tools/autotest/common.py

@ -1483,7 +1483,7 @@ class AutoTest(ABC):
continue continue
self.progress("Reached location (%.2f meters)" % delta) self.progress("Reached location (%.2f meters)" % delta)
return True return True
raise WaitLocationTimeout("Failed to attain location (want=<%f) (closest=%f)" % (accuracy, closest, last)) raise WaitLocationTimeout("Failed to attain location (want=<%f) (closest=%f) (last=%f)" % (accuracy, closest, last))
def wait_current_waypoint(self, wpnum, timeout=60): def wait_current_waypoint(self, wpnum, timeout=60):
tstart = self.get_sim_time() tstart = self.get_sim_time()

Loading…
Cancel
Save