autotest: allow max distance on ship test
vehicle moves...
This commit is contained in:
parent
3963f1b114
commit
1e4caaec78
@ -8907,7 +8907,7 @@ Also, ignores heartbeats not from our target system'''
|
|||||||
else:
|
else:
|
||||||
self.progress("Force-rebooting SITL")
|
self.progress("Force-rebooting SITL")
|
||||||
self.zero_throttle()
|
self.zero_throttle()
|
||||||
self.reboot_sitl() # that'll learn it
|
self.reboot_sitl(startup_location_dist_max=1000000) # that'll learn it
|
||||||
passed = False
|
passed = False
|
||||||
elif ardupilot_alive and not passed: # implicit reboot after a failed test:
|
elif ardupilot_alive and not passed: # implicit reboot after a failed test:
|
||||||
self.progress("Test failed but ArduPilot process alive; rebooting")
|
self.progress("Test failed but ArduPilot process alive; rebooting")
|
||||||
|
Loading…
Reference in New Issue
Block a user