autotest: don't fail completely if ArduPilot process dies

This commit is contained in:
Peter Barker 2021-05-06 10:31:38 +10:00 committed by Peter Barker
parent b305b3b074
commit f78cf73726
1 changed files with 19 additions and 4 deletions

View File

@ -1290,6 +1290,7 @@ class AutoTest(ABC):
print(formatted_text) print(formatted_text)
if (send_statustext and if (send_statustext and
self.mav is not None and self.mav is not None and
self.mav.port is not None and
self.last_progress_sent_as_statustext != text): self.last_progress_sent_as_statustext != text):
self.send_statustext(formatted_text) self.send_statustext(formatted_text)
self.last_progress_sent_as_statustext = text self.last_progress_sent_as_statustext = text
@ -5572,7 +5573,7 @@ Also, ignores heartbeats not from our target system'''
try: try:
self.mav = mavutil.mavlink_connection( self.mav = mavutil.mavlink_connection(
self.autotest_connection_string_to_ardupilot(), self.autotest_connection_string_to_ardupilot(),
retries=1000, retries=20,
robust_parsing=True, robust_parsing=True,
source_system=250, source_system=250,
source_component=250, source_component=250,
@ -5708,14 +5709,28 @@ Also, ignores heartbeats not from our target system'''
ex = e ex = e
self.test_timings[desc] = time.time() - start_time self.test_timings[desc] = time.time() - start_time
reset_needed = self.contexts[-1].sitl_commandline_customised reset_needed = self.contexts[-1].sitl_commandline_customised
self.context_pop()
passed = True passed = True
if ex is not None: if ex is not None:
passed = False passed = False
try:
self.context_pop()
except Exception as e:
self.print_exception_caught(e)
self.progress("Not alive after test", send_statustext=False)
passed = False
ardupilot_alive = False
try:
self.wait_heartbeat() self.wait_heartbeat()
if self.armed() and not self.is_tracker(): ardupilot_alive = True
except Exception:
# process is dead
passed = False
reset_needed = True
if ardupilot_alive and self.armed() and not self.is_tracker():
if ex is None: if ex is None:
ex = ArmedAtEndOfTestException("Still armed at end of test") ex = ArmedAtEndOfTestException("Still armed at end of test")
self.progress("Armed at end of test; force-rebooting SITL") self.progress("Armed at end of test; force-rebooting SITL")