mirror of https://github.com/ArduPilot/ardupilot
Merge branch 'master' of https://code.google.com/p/ardupilot-mega
This commit is contained in:
commit
3e5ec5d549
|
@ -261,8 +261,8 @@ def fly_ArduCopter():
|
|||
mavproxy.expect('Please Run Setup')
|
||||
|
||||
# we need to restart it after eeprom erase
|
||||
mavproxy.close()
|
||||
sil.close()
|
||||
util.pexpect_close(mavproxy)
|
||||
util.pexpect_close(sil)
|
||||
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.expect('Received [0-9]+ parameters')
|
||||
|
@ -272,8 +272,8 @@ def fly_ArduCopter():
|
|||
mavproxy.expect('Loaded [0-9]+ parameters')
|
||||
|
||||
# reboot with new parameters
|
||||
mavproxy.close()
|
||||
sil.close()
|
||||
util.pexpect_close(mavproxy)
|
||||
util.pexpect_close(sil)
|
||||
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.expect('Logging to (\S+)')
|
||||
|
@ -285,7 +285,6 @@ def fly_ArduCopter():
|
|||
util.expect_setup_callback(mavproxy, expect_callback)
|
||||
|
||||
# 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,
|
||||
logfile=sys.stdout, timeout=10)
|
||||
hquad.expect('Starting at')
|
||||
|
@ -313,9 +312,9 @@ def fly_ArduCopter():
|
|||
except pexpect.TIMEOUT, e:
|
||||
failed = True
|
||||
|
||||
mavproxy.close()
|
||||
sil.close()
|
||||
hquad.close()
|
||||
util.pexpect_close(mavproxy)
|
||||
util.pexpect_close(sil)
|
||||
util.pexpect_close(hquad)
|
||||
|
||||
shutil.copy(logfile, util.reltopdir("../buildlogs/ArduCopter-test.mavlog"))
|
||||
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+)'])
|
||||
if idx == 0:
|
||||
# we need to restart it after eeprom erase
|
||||
mavproxy.close()
|
||||
sil.close()
|
||||
util.pexpect_close(mavproxy)
|
||||
util.pexpect_close(sil)
|
||||
sil = util.start_SIL(atype)
|
||||
mavproxy = util.start_MAVProxy_SIL(atype)
|
||||
idx = mavproxy.expect('Saved [0-9]+ parameters to (\S+)')
|
||||
parmfile = mavproxy.match.group(1)
|
||||
dest = util.reltopdir('../buildlogs/%s.defaults.txt' % atype)
|
||||
shutil.copy(parmfile, dest)
|
||||
mavproxy.close()
|
||||
sil.close()
|
||||
util.pexpect_close(mavproxy)
|
||||
util.pexpect_close(sil)
|
||||
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.expect("logs enabled:")
|
||||
mavproxy.expect("Log]")
|
||||
mavproxy.close()
|
||||
sil.close()
|
||||
util.pexpect_close(mavproxy)
|
||||
util.pexpect_close(sil)
|
||||
log.close()
|
||||
print("Saved log for %s to %s" % (atype, logfile))
|
||||
|
||||
|
@ -88,31 +88,35 @@ def skip_step(step):
|
|||
return True
|
||||
return False
|
||||
|
||||
# kill any previous instance
|
||||
util.kill('ArduCopter.elf')
|
||||
util.kill('ArduPilot.elf')
|
||||
def run_tests(steps):
|
||||
'''run a list of steps'''
|
||||
|
||||
test_prerequesites()
|
||||
test_prerequesites()
|
||||
for step in steps:
|
||||
if skip_step(step):
|
||||
continue
|
||||
if step == 'build.ArduPlane':
|
||||
util.build_SIL('ArduPlane')
|
||||
elif step == 'build.ArduCopter':
|
||||
util.build_SIL('ArduCopter')
|
||||
elif step == 'defaults.ArduPlane':
|
||||
get_default_params('ArduPlane')
|
||||
elif step == 'defaults.ArduCopter':
|
||||
get_default_params('ArduCopter')
|
||||
elif step == 'logs.ArduPlane':
|
||||
dump_logs('ArduPlane')
|
||||
elif step == 'logs.ArduCopter':
|
||||
dump_logs('ArduCopter')
|
||||
elif step == 'fly.ArduCopter':
|
||||
arducopter.fly_ArduCopter()
|
||||
else:
|
||||
raise RuntimeError("Unknown step %s" % step)
|
||||
|
||||
for step in steps:
|
||||
if skip_step(step):
|
||||
continue
|
||||
if step == 'build.ArduPlane':
|
||||
util.build_SIL('ArduPlane')
|
||||
elif step == 'build.ArduCopter':
|
||||
util.build_SIL('ArduCopter')
|
||||
elif step == 'defaults.ArduPlane':
|
||||
get_default_params('ArduPlane')
|
||||
elif step == 'defaults.ArduCopter':
|
||||
get_default_params('ArduCopter')
|
||||
elif step == 'logs.ArduPlane':
|
||||
dump_logs('ArduPlane')
|
||||
elif step == 'logs.ArduCopter':
|
||||
dump_logs('ArduCopter')
|
||||
elif step == 'fly.ArduCopter':
|
||||
arducopter.fly_ArduCopter()
|
||||
else:
|
||||
raise RuntimeError("Unknown step %s" % step)
|
||||
|
||||
util.kill('ArduCopter.elf')
|
||||
util.kill('ArduPilot.elf')
|
||||
try:
|
||||
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),
|
||||
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):
|
||||
'''launch a SIL instance'''
|
||||
global close_list
|
||||
cmd=""
|
||||
if valgrind and os.path.exists('/usr/bin/valgrind'):
|
||||
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:
|
||||
cmd += ' -s'
|
||||
ret = pexpect.spawn(cmd, logfile=sys.stdout, timeout=5)
|
||||
close_list.append(ret)
|
||||
ret.expect('Waiting for connection')
|
||||
return ret
|
||||
|
||||
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'''
|
||||
global close_list
|
||||
MAVPROXY = reltopdir('../MAVProxy/mavproxy.py')
|
||||
cmd = MAVPROXY + ' --master=%s' % master
|
||||
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:
|
||||
cmd += ' ' + options
|
||||
ret = pexpect.spawn(cmd, logfile=logfile, timeout=60)
|
||||
close_list.append(ret)
|
||||
return ret
|
||||
|
||||
|
||||
def kill(name):
|
||||
'''kill a process'''
|
||||
run_cmd('killall -9 -q %s' % name, checkfail=False)
|
||||
|
||||
|
||||
def expect_setup_callback(e, callback):
|
||||
'''setup a callback that is called once a second while waiting for
|
||||
patterns'''
|
||||
|
|
Loading…
Reference in New Issue