mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
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!
This commit is contained in:
parent
c48042424b
commit
844999c458
@ -923,10 +923,14 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
||||
raise ex
|
||||
|
||||
def test_rally_points(self):
|
||||
self.reboot_sitl() # to ensure starting point is as expected
|
||||
|
||||
self.load_rally("rover-test-rally.txt")
|
||||
accuracy = self.get_parameter("WP_RADIUS")
|
||||
|
||||
self.wait_ready_to_arm()
|
||||
self.arm_vehicle()
|
||||
|
||||
self.reach_heading_manual(10)
|
||||
self.reach_distance_manual(50)
|
||||
|
||||
@ -936,7 +940,7 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
||||
-105.229401,
|
||||
0,
|
||||
0)
|
||||
self.wait_location(loc, accuracy=self.get_parameter("WP_RADIUS"))
|
||||
self.wait_location(loc, accuracy=accuracy)
|
||||
self.disarm_vehicle()
|
||||
|
||||
def tests(self):
|
||||
|
@ -1483,7 +1483,7 @@ class AutoTest(ABC):
|
||||
continue
|
||||
self.progress("Reached location (%.2f meters)" % delta)
|
||||
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):
|
||||
tstart = self.get_sim_time()
|
||||
|
Loading…
Reference in New Issue
Block a user