mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-12 02:48:28 -04:00
autotest: use idle_hooks to prevent lockup
This commit is contained in:
parent
af075b6ab0
commit
f9fd473df7
@ -286,6 +286,7 @@ def fly_ArduCopter(viewerip=None):
|
|||||||
print("Failed to start mavlink connection on 127.0.0.1:19550" % msg)
|
print("Failed to start mavlink connection on 127.0.0.1:19550" % msg)
|
||||||
raise
|
raise
|
||||||
mav.message_hooks.append(message_hook)
|
mav.message_hooks.append(message_hook)
|
||||||
|
mav.idle_hooks.append(idle_hook)
|
||||||
|
|
||||||
|
|
||||||
failed = False
|
failed = False
|
||||||
|
@ -4,17 +4,21 @@ import util, pexpect, time, math
|
|||||||
# messages. This keeps the output to stdout flowing
|
# messages. This keeps the output to stdout flowing
|
||||||
expect_list = []
|
expect_list = []
|
||||||
|
|
||||||
def message_hook(mav, msg):
|
def idle_hook(mav):
|
||||||
'''called as each mavlink msg is received'''
|
'''called when waiting for a mavlink message'''
|
||||||
global expect_list
|
global expect_list
|
||||||
# if msg.get_type() in [ 'NAV_CONTROLLER_OUTPUT', 'GPS_RAW' ]:
|
|
||||||
# print(msg)
|
|
||||||
for p in expect_list:
|
for p in expect_list:
|
||||||
try:
|
try:
|
||||||
p.read_nonblocking(100, timeout=0)
|
p.read_nonblocking(100, timeout=0)
|
||||||
except pexpect.TIMEOUT:
|
except pexpect.TIMEOUT:
|
||||||
pass
|
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):
|
def expect_callback(e):
|
||||||
'''called when waiting for a expect pattern'''
|
'''called when waiting for a expect pattern'''
|
||||||
global expect_list
|
global expect_list
|
||||||
|
Loading…
Reference in New Issue
Block a user