autotest: allow reboot_sitl to specify max startup loc dist

useful if your vehicle is on a ship
This commit is contained in:
Peter Barker 2023-10-20 21:03:18 +11:00 committed by Peter Barker
parent 5e929e1b39
commit 3963f1b114
1 changed files with 2 additions and 1 deletions

View File

@ -2359,6 +2359,7 @@ class TestSuite(ABC):
force=False, force=False,
check_position=True, check_position=True,
mark_context=True, mark_context=True,
startup_location_dist_max=1,
): ):
"""Reboot SITL instance and wait for it to reconnect.""" """Reboot SITL instance and wait for it to reconnect."""
if self.armed() and not force: if self.armed() and not force:
@ -2367,7 +2368,7 @@ class TestSuite(ABC):
self.reboot_sitl_mav(required_bootcount=required_bootcount, force=force) self.reboot_sitl_mav(required_bootcount=required_bootcount, force=force)
self.do_heartbeats(force=True) self.do_heartbeats(force=True)
if check_position and self.frame != 'sailboat': # sailboats drift with wind! if check_position and self.frame != 'sailboat': # sailboats drift with wind!
self.assert_simstate_location_is_at_startup_location() self.assert_simstate_location_is_at_startup_location(dist_max=startup_location_dist_max)
if mark_context: if mark_context:
self.context_get().reboot_sitl_was_done = True self.context_get().reboot_sitl_was_done = True