autotest: use idle_hooks to prevent lockup

This commit is contained in:
Andrew Tridgell 2011-11-27 18:52:54 -08:00
parent af075b6ab0
commit f9fd473df7
2 changed files with 9 additions and 4 deletions

View File

@ -286,6 +286,7 @@ def fly_ArduCopter(viewerip=None):
print("Failed to start mavlink connection on 127.0.0.1:19550" % msg)
raise
mav.message_hooks.append(message_hook)
mav.idle_hooks.append(idle_hook)
failed = False

View File

@ -4,17 +4,21 @@ import util, pexpect, time, math
# messages. This keeps the output to stdout flowing
expect_list = []
def message_hook(mav, msg):
'''called as each mavlink msg is received'''
def idle_hook(mav):
'''called when waiting for a mavlink message'''
global expect_list
# if msg.get_type() in [ 'NAV_CONTROLLER_OUTPUT', 'GPS_RAW' ]:
# print(msg)
for p in expect_list:
try:
p.read_nonblocking(100, timeout=0)
except pexpect.TIMEOUT:
pass
def message_hook(mav, msg):
'''called as each mavlink msg is received'''
# if msg.get_type() in [ 'NAV_CONTROLLER_OUTPUT', 'GPS_RAW' ]:
# print(msg)
idle_hook(mav)
def expect_callback(e):
'''called when waiting for a expect pattern'''
global expect_list