autotest: correct removal of hooks during exception handling

This commit is contained in:
Peter Barker 2024-04-29 12:56:43 +10:00 committed by Peter Barker
parent 3f0265bf58
commit f5b062562a
1 changed files with 10 additions and 6 deletions

View File

@ -6045,13 +6045,14 @@ class TestSuite(ABC):
del context.collections[msg_type]
return ret
def context_pop(self, process_interaction_allowed=True):
def context_pop(self, process_interaction_allowed=True, hooks_already_removed=False):
"""Set parameters to origin values in reverse order."""
dead = self.contexts.pop()
# remove hooks first; these hooks can raise exceptions which
# we really don't want...
for hook in dead.message_hooks:
self.remove_message_hook(hook)
if not hooks_already_removed:
for hook in dead.message_hooks:
self.remove_message_hook(hook)
for script in dead.installed_scripts:
self.remove_installed_script(script)
for (message_id, interval_us) in dead.overridden_message_rates.items():
@ -8409,7 +8410,7 @@ Also, ignores heartbeats not from our target system'''
tee = TeeBoth(test_output_filename, 'w', self.mavproxy_logfile, suppress_stdout=suppress_stdout)
start_message_hooks = self.mav.message_hooks
start_message_hooks = copy.copy(self.mav.message_hooks)
prettyname = "%s (%s)" % (name, desc)
self.start_test(prettyname)
@ -8421,6 +8422,8 @@ Also, ignores heartbeats not from our target system'''
orig_speedup = None
hooks_removed = False
ex = None
try:
self.check_rc_defaults()
@ -8444,6 +8447,7 @@ Also, ignores heartbeats not from our target system'''
for h in self.mav.message_hooks:
if h not in start_message_hooks:
self.mav.message_hooks.remove(h)
hooks_removed = True
self.test_timings[desc] = time.time() - start_time
reset_needed = self.contexts[-1].sitl_commandline_customised
@ -8470,7 +8474,7 @@ Also, ignores heartbeats not from our target system'''
reset_needed = True
try:
self.context_pop(process_interaction_allowed=ardupilot_alive)
self.context_pop(process_interaction_allowed=ardupilot_alive, hooks_already_removed=hooks_removed)
except Exception as e:
self.print_exception_caught(e, send_statustext=False)
passed = False
@ -8522,7 +8526,7 @@ Also, ignores heartbeats not from our target system'''
# pop off old contexts to clean up message hooks etc
while len(self.contexts) > old_contexts_length:
try:
self.context_pop(process_interaction_allowed=ardupilot_alive)
self.context_pop(process_interaction_allowed=ardupilot_alive, hooks_already_removed=hooks_removed)
except Exception as e:
self.print_exception_caught(e, send_statustext=False)
self.progress("Done popping extra contexts")