mirror of https://github.com/ArduPilot/ardupilot
autotest: improved error checking and child termination
we now report pass/fail for each test
This commit is contained in:
parent
4b50d2e639
commit
6089e491ed
|
@ -287,6 +287,7 @@ def fly_ArduCopter():
|
||||||
# start hil_quad.py
|
# start hil_quad.py
|
||||||
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)
|
||||||
|
util.pexpect_autoclose(hquad)
|
||||||
hquad.expect('Starting at')
|
hquad.expect('Starting at')
|
||||||
|
|
||||||
expect_list.extend([hquad, sil, mavproxy])
|
expect_list.extend([hquad, sil, mavproxy])
|
||||||
|
@ -325,5 +326,5 @@ def fly_ArduCopter():
|
||||||
|
|
||||||
if failed:
|
if failed:
|
||||||
print("FAILED: %s" % e)
|
print("FAILED: %s" % e)
|
||||||
sys.exit(1)
|
return False
|
||||||
|
return True
|
||||||
|
|
|
@ -3,7 +3,7 @@
|
||||||
# Andrew Tridgell, October 2011
|
# Andrew Tridgell, October 2011
|
||||||
|
|
||||||
import pexpect, os, util, sys, shutil, arducopter
|
import pexpect, os, util, sys, shutil, arducopter
|
||||||
import optparse, fnmatch
|
import optparse, fnmatch, time
|
||||||
|
|
||||||
os.putenv('TMPDIR', util.reltopdir('tmp'))
|
os.putenv('TMPDIR', util.reltopdir('tmp'))
|
||||||
|
|
||||||
|
@ -25,7 +25,7 @@ def get_default_params(atype):
|
||||||
util.pexpect_close(mavproxy)
|
util.pexpect_close(mavproxy)
|
||||||
util.pexpect_close(sil)
|
util.pexpect_close(sil)
|
||||||
print("Saved defaults for %s to %s" % (atype, dest))
|
print("Saved defaults for %s to %s" % (atype, dest))
|
||||||
|
return True
|
||||||
|
|
||||||
def dump_logs(atype):
|
def dump_logs(atype):
|
||||||
'''dump DataFlash logs'''
|
'''dump DataFlash logs'''
|
||||||
|
@ -48,6 +48,7 @@ def dump_logs(atype):
|
||||||
util.pexpect_close(sil)
|
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))
|
||||||
|
return True
|
||||||
|
|
||||||
def test_prerequesites():
|
def test_prerequesites():
|
||||||
'''check we have the right directories and tools to run tests'''
|
'''check we have the right directories and tools to run tests'''
|
||||||
|
@ -60,6 +61,8 @@ You need to install HILTest in %s
|
||||||
You can get it from git://git.samba.org/tridge/UAV/HILTest.git
|
You can get it from git://git.samba.org/tridge/UAV/HILTest.git
|
||||||
|
|
||||||
''' % util.reltopdir('../HILTest'))
|
''' % util.reltopdir('../HILTest'))
|
||||||
|
return False
|
||||||
|
return True
|
||||||
|
|
||||||
|
|
||||||
############## main program #############
|
############## main program #############
|
||||||
|
@ -70,9 +73,14 @@ parser.add_option("--list", action='store_true', default=False, help='list the a
|
||||||
opts, args = parser.parse_args()
|
opts, args = parser.parse_args()
|
||||||
|
|
||||||
steps = [
|
steps = [
|
||||||
|
'prerequesites',
|
||||||
|
'build1280.ArduPlane',
|
||||||
|
'build2560.ArduPlane',
|
||||||
'build.ArduPlane',
|
'build.ArduPlane',
|
||||||
'defaults.ArduPlane',
|
'defaults.ArduPlane',
|
||||||
'logs.ArduPlane',
|
'logs.ArduPlane',
|
||||||
|
'build1280.ArduCopter',
|
||||||
|
'build2560.ArduCopter',
|
||||||
'build.ArduCopter',
|
'build.ArduCopter',
|
||||||
'defaults.ArduCopter',
|
'defaults.ArduCopter',
|
||||||
'fly.ArduCopter',
|
'fly.ArduCopter',
|
||||||
|
@ -88,34 +96,74 @@ def skip_step(step):
|
||||||
return True
|
return True
|
||||||
return False
|
return False
|
||||||
|
|
||||||
|
def run_step(step):
|
||||||
|
'''run one step'''
|
||||||
|
if step == "prerequesites":
|
||||||
|
return test_prerequesites()
|
||||||
|
|
||||||
|
if step == 'build.ArduPlane':
|
||||||
|
return util.build_SIL('ArduPlane')
|
||||||
|
|
||||||
|
if step == 'build.ArduCopter':
|
||||||
|
return util.build_SIL('ArduCopter')
|
||||||
|
|
||||||
|
if step == 'build1280.ArduCopter':
|
||||||
|
return util.build_AVR('ArduCopter', board='mega')
|
||||||
|
|
||||||
|
if step == 'build2560.ArduCopter':
|
||||||
|
return util.build_AVR('ArduCopter', board='mega2560')
|
||||||
|
|
||||||
|
if step == 'build1280.ArduPlane':
|
||||||
|
return util.build_AVR('ArduPlane', board='mega')
|
||||||
|
|
||||||
|
if step == 'build2560.ArduPlane':
|
||||||
|
return util.build_AVR('ArduPlane', board='mega2560')
|
||||||
|
|
||||||
|
if step == 'defaults.ArduPlane':
|
||||||
|
return get_default_params('ArduPlane')
|
||||||
|
|
||||||
|
if step == 'defaults.ArduCopter':
|
||||||
|
return get_default_params('ArduCopter')
|
||||||
|
|
||||||
|
if step == 'logs.ArduPlane':
|
||||||
|
return dump_logs('ArduPlane')
|
||||||
|
|
||||||
|
if step == 'logs.ArduCopter':
|
||||||
|
return dump_logs('ArduCopter')
|
||||||
|
|
||||||
|
if step == 'fly.ArduCopter':
|
||||||
|
return arducopter.fly_ArduCopter()
|
||||||
|
|
||||||
|
raise RuntimeError("Unknown step %s" % step)
|
||||||
|
|
||||||
|
|
||||||
def run_tests(steps):
|
def run_tests(steps):
|
||||||
'''run a list of steps'''
|
'''run a list of steps'''
|
||||||
|
|
||||||
test_prerequesites()
|
passed = True
|
||||||
for step in steps:
|
for step in steps:
|
||||||
if skip_step(step):
|
if skip_step(step):
|
||||||
continue
|
continue
|
||||||
if step == 'build.ArduPlane':
|
|
||||||
util.build_SIL('ArduPlane')
|
print(">>>> RUNNING STEP: %s at %s" % (step, time.asctime()))
|
||||||
elif step == 'build.ArduCopter':
|
try:
|
||||||
util.build_SIL('ArduCopter')
|
if not run_step(step):
|
||||||
elif step == 'defaults.ArduPlane':
|
print(">>>> FAILED STEP: %s at %s" % (step, time.asctime()))
|
||||||
get_default_params('ArduPlane')
|
passed = False
|
||||||
elif step == 'defaults.ArduCopter':
|
continue
|
||||||
get_default_params('ArduCopter')
|
except Exception, msg:
|
||||||
elif step == 'logs.ArduPlane':
|
passed = False
|
||||||
dump_logs('ArduPlane')
|
print(">>>> FAILED STEP: %s at %s (%s)" % (step, time.asctime(), msg))
|
||||||
elif step == 'logs.ArduCopter':
|
continue
|
||||||
dump_logs('ArduCopter')
|
print(">>>> PASSED STEP: %s at %s" % (step, time.asctime()))
|
||||||
elif step == 'fly.ArduCopter':
|
return passed
|
||||||
arducopter.fly_ArduCopter()
|
|
||||||
else:
|
|
||||||
raise RuntimeError("Unknown step %s" % step)
|
|
||||||
|
|
||||||
try:
|
try:
|
||||||
run_tests(steps)
|
if not run_tests(steps):
|
||||||
|
sys.exit(1)
|
||||||
except KeyboardInterrupt:
|
except KeyboardInterrupt:
|
||||||
util.pexpect_close_all()
|
util.pexpect_close_all()
|
||||||
|
sys.exit(1)
|
||||||
except Exception:
|
except Exception:
|
||||||
# make sure we kill off any children
|
# make sure we kill off any children
|
||||||
util.pexpect_close_all()
|
util.pexpect_close_all()
|
||||||
|
|
|
@ -47,13 +47,33 @@ def build_SIL(atype):
|
||||||
run_cmd("make -f ../libraries/Desktop/Makefile.desktop clean hil",
|
run_cmd("make -f ../libraries/Desktop/Makefile.desktop clean hil",
|
||||||
dir=reltopdir(atype),
|
dir=reltopdir(atype),
|
||||||
checkfail=True)
|
checkfail=True)
|
||||||
|
return True
|
||||||
|
|
||||||
|
def build_AVR(atype, board='mega2560'):
|
||||||
|
'''build AVR binaries'''
|
||||||
|
config = open(reltopdir('config.mk'), mode='w')
|
||||||
|
config.write('''
|
||||||
|
BOARD=%s
|
||||||
|
PORT=/dev/null
|
||||||
|
''' % board)
|
||||||
|
config.close()
|
||||||
|
run_cmd("make clean", dir=reltopdir(atype), checkfail=True)
|
||||||
|
run_cmd("make", dir=reltopdir(atype), checkfail=True)
|
||||||
|
return True
|
||||||
|
|
||||||
|
|
||||||
|
# list of pexpect children to close on exit
|
||||||
close_list = []
|
close_list = []
|
||||||
|
|
||||||
|
def pexpect_autoclose(p):
|
||||||
|
'''mark for autoclosing'''
|
||||||
|
global close_list
|
||||||
|
close_list.append(p)
|
||||||
|
|
||||||
def pexpect_close(p):
|
def pexpect_close(p):
|
||||||
'''close a pexpect child'''
|
'''close a pexpect child'''
|
||||||
global close_list
|
global close_list
|
||||||
p.close()
|
p.close(force=True)
|
||||||
close_list.remove(p)
|
close_list.remove(p)
|
||||||
|
|
||||||
def pexpect_close_all():
|
def pexpect_close_all():
|
||||||
|
@ -61,13 +81,12 @@ def pexpect_close_all():
|
||||||
global close_list
|
global close_list
|
||||||
for p in close_list[:]:
|
for p in close_list[:]:
|
||||||
try:
|
try:
|
||||||
p.close()
|
p.close(Force=True)
|
||||||
except Exception:
|
except Exception:
|
||||||
pass
|
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
|
||||||
|
@ -77,7 +96,7 @@ 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)
|
pexpect_autoclose(ret)
|
||||||
ret.expect('Waiting for connection')
|
ret.expect('Waiting for connection')
|
||||||
return ret
|
return ret
|
||||||
|
|
||||||
|
@ -95,7 +114,7 @@ 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)
|
pexpect_autoclose(ret)
|
||||||
return ret
|
return ret
|
||||||
|
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue