mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 18:38:28 -04:00
autotest: avoid the need for killall
this ensures we cleanup child processes cleanly, so we don't need the killall any more
This commit is contained in:
parent
ccc2746a22
commit
e373c2a8b6
@ -261,8 +261,8 @@ def fly_ArduCopter():
|
|||||||
mavproxy.expect('Please Run Setup')
|
mavproxy.expect('Please Run Setup')
|
||||||
|
|
||||||
# we need to restart it after eeprom erase
|
# we need to restart it after eeprom erase
|
||||||
mavproxy.close()
|
util.pexpect_close(mavproxy)
|
||||||
sil.close()
|
util.pexpect_close(sil)
|
||||||
sil = util.start_SIL('ArduCopter')
|
sil = util.start_SIL('ArduCopter')
|
||||||
mavproxy = util.start_MAVProxy_SIL('ArduCopter', options='--fgout=127.0.0.1:5502 --fgin=127.0.0.1:5501 --out=127.0.0.1:14550 --quadcopter')
|
mavproxy = util.start_MAVProxy_SIL('ArduCopter', options='--fgout=127.0.0.1:5502 --fgin=127.0.0.1:5501 --out=127.0.0.1:14550 --quadcopter')
|
||||||
mavproxy.expect('Received [0-9]+ parameters')
|
mavproxy.expect('Received [0-9]+ parameters')
|
||||||
@ -272,8 +272,8 @@ def fly_ArduCopter():
|
|||||||
mavproxy.expect('Loaded [0-9]+ parameters')
|
mavproxy.expect('Loaded [0-9]+ parameters')
|
||||||
|
|
||||||
# reboot with new parameters
|
# reboot with new parameters
|
||||||
mavproxy.close()
|
util.pexpect_close(mavproxy)
|
||||||
sil.close()
|
util.pexpect_close(sil)
|
||||||
sil = util.start_SIL('ArduCopter')
|
sil = util.start_SIL('ArduCopter')
|
||||||
mavproxy = util.start_MAVProxy_SIL('ArduCopter', options='--fgout=127.0.0.1:5502 --fgin=127.0.0.1:5501 --out=127.0.0.1:14550 --out=192.168.2.15:14550 --quadcopter --streamrate=1')
|
mavproxy = util.start_MAVProxy_SIL('ArduCopter', options='--fgout=127.0.0.1:5502 --fgin=127.0.0.1:5501 --out=127.0.0.1:14550 --out=192.168.2.15:14550 --quadcopter --streamrate=1')
|
||||||
mavproxy.expect('Logging to (\S+)')
|
mavproxy.expect('Logging to (\S+)')
|
||||||
@ -285,7 +285,6 @@ def fly_ArduCopter():
|
|||||||
util.expect_setup_callback(mavproxy, expect_callback)
|
util.expect_setup_callback(mavproxy, expect_callback)
|
||||||
|
|
||||||
# start hil_quad.py
|
# start hil_quad.py
|
||||||
util.run_cmd('pkill -f hil_quad.py', checkfail=False)
|
|
||||||
hquad = pexpect.spawn(util.reltopdir('../HILTest/hil_quad.py') + ' --fgout=192.168.2.15:9123 --home=%s' % HOME_LOCATION,
|
hquad = pexpect.spawn(util.reltopdir('../HILTest/hil_quad.py') + ' --fgout=192.168.2.15:9123 --home=%s' % HOME_LOCATION,
|
||||||
logfile=sys.stdout, timeout=10)
|
logfile=sys.stdout, timeout=10)
|
||||||
hquad.expect('Starting at')
|
hquad.expect('Starting at')
|
||||||
@ -313,9 +312,9 @@ def fly_ArduCopter():
|
|||||||
except pexpect.TIMEOUT, e:
|
except pexpect.TIMEOUT, e:
|
||||||
failed = True
|
failed = True
|
||||||
|
|
||||||
mavproxy.close()
|
util.pexpect_close(mavproxy)
|
||||||
sil.close()
|
util.pexpect_close(sil)
|
||||||
hquad.close()
|
util.pexpect_close(hquad)
|
||||||
|
|
||||||
shutil.copy(logfile, util.reltopdir("../buildlogs/ArduCopter-test.mavlog"))
|
shutil.copy(logfile, util.reltopdir("../buildlogs/ArduCopter-test.mavlog"))
|
||||||
if os.path.exists('ArduCopter-valgrind.log'):
|
if os.path.exists('ArduCopter-valgrind.log'):
|
||||||
|
@ -14,16 +14,16 @@ def get_default_params(atype):
|
|||||||
idx = mavproxy.expect(['Please Run Setup', 'Saved [0-9]+ parameters to (\S+)'])
|
idx = mavproxy.expect(['Please Run Setup', 'Saved [0-9]+ parameters to (\S+)'])
|
||||||
if idx == 0:
|
if idx == 0:
|
||||||
# we need to restart it after eeprom erase
|
# we need to restart it after eeprom erase
|
||||||
mavproxy.close()
|
util.pexpect_close(mavproxy)
|
||||||
sil.close()
|
util.pexpect_close(sil)
|
||||||
sil = util.start_SIL(atype)
|
sil = util.start_SIL(atype)
|
||||||
mavproxy = util.start_MAVProxy_SIL(atype)
|
mavproxy = util.start_MAVProxy_SIL(atype)
|
||||||
idx = mavproxy.expect('Saved [0-9]+ parameters to (\S+)')
|
idx = mavproxy.expect('Saved [0-9]+ parameters to (\S+)')
|
||||||
parmfile = mavproxy.match.group(1)
|
parmfile = mavproxy.match.group(1)
|
||||||
dest = util.reltopdir('../buildlogs/%s.defaults.txt' % atype)
|
dest = util.reltopdir('../buildlogs/%s.defaults.txt' % atype)
|
||||||
shutil.copy(parmfile, dest)
|
shutil.copy(parmfile, dest)
|
||||||
mavproxy.close()
|
util.pexpect_close(mavproxy)
|
||||||
sil.close()
|
util.pexpect_close(sil)
|
||||||
print("Saved defaults for %s to %s" % (atype, dest))
|
print("Saved defaults for %s to %s" % (atype, dest))
|
||||||
|
|
||||||
|
|
||||||
@ -44,8 +44,8 @@ def dump_logs(atype):
|
|||||||
mavproxy.send("dump %u\n" % (i+1))
|
mavproxy.send("dump %u\n" % (i+1))
|
||||||
mavproxy.expect("logs enabled:")
|
mavproxy.expect("logs enabled:")
|
||||||
mavproxy.expect("Log]")
|
mavproxy.expect("Log]")
|
||||||
mavproxy.close()
|
util.pexpect_close(mavproxy)
|
||||||
sil.close()
|
util.pexpect_close(sil)
|
||||||
log.close()
|
log.close()
|
||||||
print("Saved log for %s to %s" % (atype, logfile))
|
print("Saved log for %s to %s" % (atype, logfile))
|
||||||
|
|
||||||
@ -88,13 +88,11 @@ def skip_step(step):
|
|||||||
return True
|
return True
|
||||||
return False
|
return False
|
||||||
|
|
||||||
# kill any previous instance
|
def run_tests(steps):
|
||||||
util.kill('ArduCopter.elf')
|
'''run a list of steps'''
|
||||||
util.kill('ArduPilot.elf')
|
|
||||||
|
|
||||||
test_prerequesites()
|
test_prerequesites()
|
||||||
|
for step in steps:
|
||||||
for step in steps:
|
|
||||||
if skip_step(step):
|
if skip_step(step):
|
||||||
continue
|
continue
|
||||||
if step == 'build.ArduPlane':
|
if step == 'build.ArduPlane':
|
||||||
@ -114,5 +112,11 @@ for step in steps:
|
|||||||
else:
|
else:
|
||||||
raise RuntimeError("Unknown step %s" % step)
|
raise RuntimeError("Unknown step %s" % step)
|
||||||
|
|
||||||
util.kill('ArduCopter.elf')
|
try:
|
||||||
util.kill('ArduPilot.elf')
|
run_tests(steps)
|
||||||
|
except KeyboardInterrupt:
|
||||||
|
util.pexpect_close_all()
|
||||||
|
except Exception:
|
||||||
|
# make sure we kill off any children
|
||||||
|
util.pexpect_close_all()
|
||||||
|
raise
|
||||||
|
@ -48,8 +48,26 @@ def build_SIL(atype):
|
|||||||
dir=reltopdir(atype),
|
dir=reltopdir(atype),
|
||||||
checkfail=True)
|
checkfail=True)
|
||||||
|
|
||||||
|
close_list = []
|
||||||
|
|
||||||
|
def pexpect_close(p):
|
||||||
|
'''close a pexpect child'''
|
||||||
|
global close_list
|
||||||
|
p.close()
|
||||||
|
close_list.remove(p)
|
||||||
|
|
||||||
|
def pexpect_close_all():
|
||||||
|
'''close all pexpect children'''
|
||||||
|
global close_list
|
||||||
|
for p in close_list[:]:
|
||||||
|
try:
|
||||||
|
p.close()
|
||||||
|
except Exception:
|
||||||
|
pass
|
||||||
|
|
||||||
def start_SIL(atype, valgrind=True, wipe=False, CLI=False):
|
def start_SIL(atype, valgrind=True, wipe=False, CLI=False):
|
||||||
'''launch a SIL instance'''
|
'''launch a SIL instance'''
|
||||||
|
global close_list
|
||||||
cmd=""
|
cmd=""
|
||||||
if valgrind and os.path.exists('/usr/bin/valgrind'):
|
if valgrind and os.path.exists('/usr/bin/valgrind'):
|
||||||
cmd += 'valgrind -q --log-file=%s-valgrind.log ' % atype
|
cmd += 'valgrind -q --log-file=%s-valgrind.log ' % atype
|
||||||
@ -59,12 +77,14 @@ def start_SIL(atype, valgrind=True, wipe=False, CLI=False):
|
|||||||
if CLI:
|
if CLI:
|
||||||
cmd += ' -s'
|
cmd += ' -s'
|
||||||
ret = pexpect.spawn(cmd, logfile=sys.stdout, timeout=5)
|
ret = pexpect.spawn(cmd, logfile=sys.stdout, timeout=5)
|
||||||
|
close_list.append(ret)
|
||||||
ret.expect('Waiting for connection')
|
ret.expect('Waiting for connection')
|
||||||
return ret
|
return ret
|
||||||
|
|
||||||
def start_MAVProxy_SIL(atype, aircraft=None, setup=False, master='tcp:127.0.0.1:5760',
|
def start_MAVProxy_SIL(atype, aircraft=None, setup=False, master='tcp:127.0.0.1:5760',
|
||||||
options=None, logfile=sys.stdout):
|
options=None, logfile=sys.stdout):
|
||||||
'''launch mavproxy connected to a SIL instance'''
|
'''launch mavproxy connected to a SIL instance'''
|
||||||
|
global close_list
|
||||||
MAVPROXY = reltopdir('../MAVProxy/mavproxy.py')
|
MAVPROXY = reltopdir('../MAVProxy/mavproxy.py')
|
||||||
cmd = MAVPROXY + ' --master=%s' % master
|
cmd = MAVPROXY + ' --master=%s' % master
|
||||||
if setup:
|
if setup:
|
||||||
@ -75,14 +95,10 @@ def start_MAVProxy_SIL(atype, aircraft=None, setup=False, master='tcp:127.0.0.1:
|
|||||||
if options is not None:
|
if options is not None:
|
||||||
cmd += ' ' + options
|
cmd += ' ' + options
|
||||||
ret = pexpect.spawn(cmd, logfile=logfile, timeout=60)
|
ret = pexpect.spawn(cmd, logfile=logfile, timeout=60)
|
||||||
|
close_list.append(ret)
|
||||||
return ret
|
return ret
|
||||||
|
|
||||||
|
|
||||||
def kill(name):
|
|
||||||
'''kill a process'''
|
|
||||||
run_cmd('killall -9 -q %s' % name, checkfail=False)
|
|
||||||
|
|
||||||
|
|
||||||
def expect_setup_callback(e, callback):
|
def expect_setup_callback(e, callback):
|
||||||
'''setup a callback that is called once a second while waiting for
|
'''setup a callback that is called once a second while waiting for
|
||||||
patterns'''
|
patterns'''
|
||||||
|
Loading…
Reference in New Issue
Block a user