autotest: enable dumping of DataFlash logs at end of test

This commit is contained in:
Andrew Tridgell 2011-11-07 22:55:21 +11:00
parent a199835632
commit 5e5d86ca09
4 changed files with 51 additions and 14 deletions

View File

@ -1,4 +1,5 @@
FRAME 0 FRAME 0
LOG_BITMASK 4095
RC1_MAX 2000.000000 RC1_MAX 2000.000000
RC1_MIN 1000.000000 RC1_MIN 1000.000000
RC1_TRIM 1500.000000 RC1_TRIM 1500.000000

View File

@ -256,8 +256,7 @@ def fly_ArduCopter():
'''fly ArduCopter in SIL''' '''fly ArduCopter in SIL'''
global expect_list, homeloc global expect_list, homeloc
util.rmfile('eeprom.bin') sil = util.start_SIL('ArduCopter', wipe=True)
sil = util.start_SIL('ArduCopter')
mavproxy = util.start_MAVProxy_SIL('ArduCopter') mavproxy = util.start_MAVProxy_SIL('ArduCopter')
mavproxy.expect('Please Run Setup') mavproxy.expect('Please Run Setup')

View File

@ -9,8 +9,7 @@ os.putenv('TMPDIR', util.reltopdir('tmp'))
def get_default_params(atype): def get_default_params(atype):
'''get default parameters''' '''get default parameters'''
util.rmfile('eeprom.bin') sil = util.start_SIL(atype, wipe=True)
sil = util.start_SIL(atype)
mavproxy = util.start_MAVProxy_SIL(atype) mavproxy = util.start_MAVProxy_SIL(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:
@ -27,6 +26,24 @@ def get_default_params(atype):
sil.close() sil.close()
print("Saved defaults for %s to %s" % (atype, dest)) print("Saved defaults for %s to %s" % (atype, dest))
def dump_logs(atype):
'''dump DataFlash logs'''
print("Dumping logs for %s" % atype)
sil = util.start_SIL(atype, CLI=True)
logfile = util.reltopdir('../buildlogs/%s.flashlog' % atype)
log = open(logfile, mode='w')
mavproxy = util.start_MAVProxy_SIL(atype, setup=True, logfile=log)
mavproxy.expect(']')
mavproxy.send("logs\n")
mavproxy.expect("Log]")
mavproxy.send("dump 1\n")
mavproxy.expect("Log]")
mavproxy.close()
sil.close()
log.close()
print("Saved log for %s to %s" % (atype, logfile))
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'''
print("Testing prerequesites") print("Testing prerequesites")
@ -49,10 +66,12 @@ opts, args = parser.parse_args()
steps = [ steps = [
'build.ArduPlane', 'build.ArduPlane',
'build.ArduCopter',
'defaults.ArduPlane', 'defaults.ArduPlane',
'logs.ArduPlane',
'build.ArduCopter',
'defaults.ArduCopter', 'defaults.ArduCopter',
'fly.ArduCopter' 'fly.ArduCopter',
'logs.ArduCopter',
] ]
skipsteps = opts.skip.split(',') skipsteps = opts.skip.split(',')
@ -81,6 +100,10 @@ for step in steps:
get_default_params('ArduPlane') get_default_params('ArduPlane')
elif step == 'defaults.ArduCopter': elif step == 'defaults.ArduCopter':
get_default_params('ArduCopter') get_default_params('ArduCopter')
elif step == 'logs.ArduPlane':
dump_logs('ArduPlane')
elif step == 'logs.ArduCopter':
dump_logs('ArduCopter')
elif step == 'fly.ArduCopter': elif step == 'fly.ArduCopter':
arducopter.fly_ArduCopter() arducopter.fly_ArduCopter()
else: else:

View File

@ -32,7 +32,7 @@ def run_cmd(cmd, dir=".", show=False, output=False, checkfail=True):
def rmfile(path): def rmfile(path):
'''remove a file if it exists''' '''remove a file if it exists'''
try: try:
os.unlink('eeprom.bin') os.unlink(path)
except Exception: except Exception:
pass pass
@ -48,19 +48,33 @@ def build_SIL(atype):
dir=reltopdir(atype), dir=reltopdir(atype),
checkfail=True) checkfail=True)
def start_SIL(atype): def start_SIL(atype, valgrind=True, wipe=False, CLI=False):
'''launch a SIL instance''' '''launch a SIL instance'''
ret = pexpect.spawn(('valgrind -q --log-file=%s-valgrind.log ' % atype) + reltopdir('tmp/%s.build/%s.elf' % (atype, atype)), cmd=""
logfile=sys.stdout, timeout=5) if valgrind:
cmd += 'valgrind -q --log-file=%s-valgrind.log ' % atype
cmd += reltopdir('tmp/%s.build/%s.elf' % (atype, atype))
if wipe:
cmd += ' -w'
if CLI:
cmd += ' -s'
ret = pexpect.spawn(cmd, logfile=sys.stdout, timeout=5)
ret.expect('Waiting for connection') ret.expect('Waiting for connection')
return ret return ret
def start_MAVProxy_SIL(atype, options=''): def start_MAVProxy_SIL(atype, aircraft=None, setup=False, master='tcp:127.0.0.1:5760',
options=None, logfile=sys.stdout):
'''launch mavproxy connected to a SIL instance''' '''launch mavproxy connected to a SIL instance'''
MAVPROXY = reltopdir('../MAVProxy/mavproxy.py') MAVPROXY = reltopdir('../MAVProxy/mavproxy.py')
ret = pexpect.spawn('%s --master=tcp:127.0.0.1:5760 --aircraft=test.%s %s' % ( cmd = MAVPROXY + ' --master=%s' % master
MAVPROXY,atype,options), if setup:
logfile=sys.stdout, timeout=60) cmd += ' --setup'
if aircraft is None:
aircraft = 'test.%s' % atype
cmd += ' --aircraft=%s' % aircraft
if options is not None:
cmd += ' ' + options
ret = pexpect.spawn(cmd, logfile=logfile, timeout=60)
return ret return ret