autotest: correct behaviour when process dies

interacting with the dead process isn't going to work
This commit is contained in:
Peter Barker 2023-02-16 15:25:47 +11:00 committed by Peter Barker
parent 2d862758e7
commit 96ae4367a2

View File

@ -201,7 +201,8 @@ class Context(object):
# https://stackoverflow.com/questions/616645/how-do-i-duplicate-sys-stdout-to-a-log-file-in-python # https://stackoverflow.com/questions/616645/how-do-i-duplicate-sys-stdout-to-a-log-file-in-python
class TeeBoth(object): class TeeBoth(object):
def __init__(self, name, mode, mavproxy_logfile): def __init__(self, name, mode, mavproxy_logfile, suppress_stdout=False):
self.suppress_stdout = suppress_stdout
self.file = open(name, mode) self.file = open(name, mode)
self.stdout = sys.stdout self.stdout = sys.stdout
self.stderr = sys.stderr self.stderr = sys.stderr
@ -220,7 +221,8 @@ class TeeBoth(object):
def write(self, data): def write(self, data):
self.file.write(data) self.file.write(data)
self.stdout.write(data) if not self.suppress_stdout:
self.stdout.write(data)
def flush(self): def flush(self):
self.file.flush() self.file.flush()
@ -5652,7 +5654,7 @@ class AutoTest(ABC):
del context.collections[msg_type] del context.collections[msg_type]
return ret return ret
def context_pop(self): def context_pop(self, process_interaction_allowed=True):
"""Set parameters to origin values in reverse order.""" """Set parameters to origin values in reverse order."""
dead = self.contexts.pop() dead = self.contexts.pop()
# remove hooks first; these hooks can raise exceptions which # remove hooks first; these hooks can raise exceptions which
@ -5670,7 +5672,8 @@ class AutoTest(ABC):
dead_parameters_dict = {} dead_parameters_dict = {}
for p in dead.parameters: for p in dead.parameters:
dead_parameters_dict[p[0]] = p[1] dead_parameters_dict[p[0]] = p[1]
self.set_parameters(dead_parameters_dict, add_to_context=False) if process_interaction_allowed:
self.set_parameters(dead_parameters_dict, add_to_context=False)
if getattr(self, "old_binary", None) is not None: if getattr(self, "old_binary", None) is not None:
self.stop_SITL() self.stop_SITL()
@ -7791,14 +7794,14 @@ Also, ignores heartbeats not from our target system'''
util.run_cmd('/bin/cp build/sitl/bin/* %s' % to_dir, util.run_cmd('/bin/cp build/sitl/bin/* %s' % to_dir,
directory=util.reltopdir('.')) directory=util.reltopdir('.'))
def run_one_test(self, test, interact=False): def run_one_test(self, test, interact=False, suppress_stdout=False):
'''new-style run-one-test used by run_tests''' '''new-style run-one-test used by run_tests'''
for i in range(0, test.attempts-1): for i in range(0, test.attempts-1):
result = self.run_one_test_attempt(test, interact=interact, attempt=i+2) result = self.run_one_test_attempt(test, interact=interact, attempt=i+2, suppress_stdout=suppress_stdout)
if result.passed: if result.passed:
return result return result
self.progress("Run attempt failed. Retrying") self.progress("Run attempt failed. Retrying")
return self.run_one_test_attempt(test, interact=interact, attempt=1) return self.run_one_test_attempt(test, interact=interact, attempt=1, suppress_stdout=suppress_stdout)
def print_exception_caught(self, e, send_statustext=True): def print_exception_caught(self, e, send_statustext=True):
self.progress("Exception caught: %s" % self.progress("Exception caught: %s" %
@ -7815,7 +7818,31 @@ Also, ignores heartbeats not from our target system'''
for line in f: for line in f:
self.progress(line.rstrip()) self.progress(line.rstrip())
def run_one_test_attempt(self, test, interact=False, attempt=1): def dump_process_status(self, result):
'''used to show where the SITL process is upto. Often caused when
we've lost contact'''
if self.sitl.isalive():
self.progress("pexpect says it is alive")
for tool in "dumpstack.sh", "dumpcore.sh":
tool_filepath = os.path.join(self.rootdir(), 'Tools', 'scripts', tool)
if util.run_cmd([tool_filepath, str(self.sitl.pid)]) != 0:
reason = "Failed %s" % (tool,)
self.progress(reason)
result.reason = reason
result.passed = False
else:
self.progress("pexpect says it is dead")
# try dumping the process status file for more information:
status_filepath = "/proc/%u/status" % self.sitl.pid
self.progress("Checking for status filepath (%s)" % status_filepath)
if os.path.exists(status_filepath):
self.progress_file_content(status_filepath)
else:
self.progress("... does not exist")
def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout=False):
'''called by run_one_test to actually run the test in a retry loop''' '''called by run_one_test to actually run the test in a retry loop'''
name = test.name name = test.name
desc = test.description desc = test.description
@ -7828,7 +7855,7 @@ Also, ignores heartbeats not from our target system'''
test_output_filename = self.buildlogs_path("%s-%s.txt" % test_output_filename = self.buildlogs_path("%s-%s.txt" %
(self.log_name(), name)) (self.log_name(), name))
tee = TeeBoth(test_output_filename, 'w', self.mavproxy_logfile) tee = TeeBoth(test_output_filename, 'w', self.mavproxy_logfile, suppress_stdout=suppress_stdout)
start_message_hooks = self.mav.message_hooks start_message_hooks = self.mav.message_hooks
@ -7875,12 +7902,6 @@ Also, ignores heartbeats not from our target system'''
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, send_statustext=False)
passed = False
result = Result(test) result = Result(test)
ardupilot_alive = False ardupilot_alive = False
@ -7890,29 +7911,17 @@ Also, ignores heartbeats not from our target system'''
except Exception: except Exception:
# process is dead # process is dead
self.progress("No heartbeat after test", send_statustext=False) self.progress("No heartbeat after test", send_statustext=False)
if self.sitl.isalive(): self.dump_process_status(result)
self.progress("pexpect says it is alive")
for tool in "dumpstack.sh", "dumpcore.sh":
tool_filepath = os.path.join(self.rootdir(), 'Tools', 'scripts', tool)
if util.run_cmd([tool_filepath, str(self.sitl.pid)]) != 0:
self.progress("Failed %s" % (tool,))
result.description
result.passed = False
return result
else:
self.progress("pexpect says it is dead")
# try dumping the process status file for more information:
status_filepath = "/proc/%u/status" % self.sitl.pid
self.progress("Checking for status filepath (%s)" % status_filepath)
if os.path.exists(status_filepath):
self.progress_file_content(status_filepath)
else:
self.progress("... does not exist")
passed = False passed = False
reset_needed = True reset_needed = True
try:
self.context_pop(process_interaction_allowed=ardupilot_alive)
except Exception as e:
self.print_exception_caught(e, send_statustext=False)
passed = False
# if we haven't already reset ArduPilot because it's dead, # if we haven't already reset ArduPilot because it's dead,
# then ensure the vehicle was disarmed at the end of the test. # then ensure the vehicle was disarmed at the end of the test.
# If it wasn't then the test is considered failed: # If it wasn't then the test is considered failed:
@ -7932,7 +7941,7 @@ Also, ignores heartbeats not from our target system'''
self.progress("Force-rebooting SITL") self.progress("Force-rebooting SITL")
self.reboot_sitl() # that'll learn it self.reboot_sitl() # that'll learn it
passed = False passed = False
elif 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")
self.reboot_sitl() # that'll learn it self.reboot_sitl() # that'll learn it
@ -7960,7 +7969,7 @@ Also, ignores heartbeats not from our target system'''
# pop off old contexts to clean up message hooks etc # pop off old contexts to clean up message hooks etc
while len(self.contexts) > old_contexts_length: while len(self.contexts) > old_contexts_length:
try: try:
self.context_pop() self.context_pop(process_interaction_allowed=ardupilot_alive)
except Exception as e: except Exception as e:
self.print_exception_caught(e, send_statustext=False) self.print_exception_caught(e, send_statustext=False)
self.progress("Done popping extra contexts") self.progress("Done popping extra contexts")