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
This commit is contained in:
Peter Barker 2022-12-27 09:09:44 +11:00 committed by Peter Barker
parent da0927b076
commit 89ecd8fb17

View File

@ -1128,6 +1128,7 @@ class AutoTestCopter(AutoTest):
self.change_mode(mode) self.change_mode(mode)
self.zero_throttle() self.zero_throttle()
self.wait_ready_to_arm() self.wait_ready_to_arm()
self.context_push()
self.context_collect('STATUSTEXT') self.context_collect('STATUSTEXT')
self.send_mavlink_arm_command() self.send_mavlink_arm_command()
self.mav.recv_match(blocking=True, timeout=1) self.mav.recv_match(blocking=True, timeout=1)
@ -1137,6 +1138,7 @@ class AutoTestCopter(AutoTest):
self.set_rc(3, 1700) self.set_rc(3, 1700)
# we may never see ourselves as armed in a heartbeat # we may never see ourselves as armed in a heartbeat
self.wait_statustext("Takeoff blocked: ESC RPM too low", check_context=True) self.wait_statustext("Takeoff blocked: ESC RPM too low", check_context=True)
self.context_pop()
self.zero_throttle() self.zero_throttle()
self.disarm_vehicle() self.disarm_vehicle()
self.wait_disarmed() self.wait_disarmed()