From 89ecd8fb17010f17344f23791592a9211306b4f1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 27 Dec 2022 09:09:44 +1100 Subject: [PATCH] autotest: create a context-per-check whentesting motors blocked without this all subsequent tests will find the string in the context's collection of statustexts. So use a context-per-mode --- Tools/autotest/arducopter.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index dddcb9708f..8ac495a8de 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -1128,6 +1128,7 @@ class AutoTestCopter(AutoTest): self.change_mode(mode) self.zero_throttle() self.wait_ready_to_arm() + self.context_push() self.context_collect('STATUSTEXT') self.send_mavlink_arm_command() self.mav.recv_match(blocking=True, timeout=1) @@ -1137,6 +1138,7 @@ class AutoTestCopter(AutoTest): self.set_rc(3, 1700) # we may never see ourselves as armed in a heartbeat self.wait_statustext("Takeoff blocked: ESC RPM too low", check_context=True) + self.context_pop() self.zero_throttle() self.disarm_vehicle() self.wait_disarmed()