2011-10-30 23:50:34 -03:00
|
|
|
# utility code for autotest
|
|
|
|
|
2011-11-01 08:31:01 -03:00
|
|
|
import os, pexpect, sys, time
|
2011-10-30 23:50:34 -03:00
|
|
|
from subprocess import call, check_call,Popen, PIPE
|
|
|
|
|
|
|
|
|
2011-11-01 08:31:01 -03:00
|
|
|
def topdir():
|
|
|
|
'''return top of git tree where autotest is running from'''
|
|
|
|
d = os.path.dirname(os.path.realpath(__file__))
|
|
|
|
assert(os.path.basename(d)=='autotest')
|
|
|
|
d = os.path.dirname(d)
|
|
|
|
assert(os.path.basename(d)=='Tools')
|
|
|
|
d = os.path.dirname(d)
|
|
|
|
return d
|
2011-10-30 23:50:34 -03:00
|
|
|
|
2011-11-01 08:31:01 -03:00
|
|
|
def reltopdir(path):
|
|
|
|
'''return a path relative to topdir()'''
|
|
|
|
return os.path.normpath(os.path.join(topdir(), path))
|
2011-10-30 23:50:34 -03:00
|
|
|
|
|
|
|
|
|
|
|
def run_cmd(cmd, dir=".", show=False, output=False, checkfail=True):
|
|
|
|
'''run a shell command'''
|
|
|
|
if show:
|
|
|
|
print("Running: '%s' in '%s'" % (cmd, dir))
|
|
|
|
if output:
|
|
|
|
return Popen([cmd], shell=True, stdout=PIPE, cwd=dir).communicate()[0]
|
|
|
|
elif checkfail:
|
|
|
|
return check_call(cmd, shell=True, cwd=dir)
|
|
|
|
else:
|
|
|
|
return call(cmd, shell=True, cwd=dir)
|
|
|
|
|
|
|
|
def rmfile(path):
|
|
|
|
'''remove a file if it exists'''
|
|
|
|
try:
|
2011-11-07 07:55:21 -04:00
|
|
|
os.unlink(path)
|
2011-10-30 23:50:34 -03:00
|
|
|
except Exception:
|
|
|
|
pass
|
|
|
|
|
|
|
|
def deltree(path):
|
|
|
|
'''delete a tree of files'''
|
|
|
|
run_cmd('rm -rf %s' % path)
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
def build_SIL(atype):
|
|
|
|
'''build desktop SIL'''
|
|
|
|
run_cmd("make -f ../libraries/Desktop/Makefile.desktop clean hil",
|
2011-11-01 08:31:01 -03:00
|
|
|
dir=reltopdir(atype),
|
2011-10-30 23:50:34 -03:00
|
|
|
checkfail=True)
|
2011-11-09 01:15:53 -04:00
|
|
|
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
|
2011-11-09 00:45:18 -04:00
|
|
|
close_list = []
|
|
|
|
|
2011-11-09 01:15:53 -04:00
|
|
|
def pexpect_autoclose(p):
|
|
|
|
'''mark for autoclosing'''
|
|
|
|
global close_list
|
|
|
|
close_list.append(p)
|
|
|
|
|
2011-11-09 00:45:18 -04:00
|
|
|
def pexpect_close(p):
|
|
|
|
'''close a pexpect child'''
|
|
|
|
global close_list
|
2011-11-09 02:44:14 -04:00
|
|
|
p.close()
|
|
|
|
time.sleep(1)
|
2011-11-09 01:15:53 -04:00
|
|
|
p.close(force=True)
|
2011-11-09 02:44:14 -04:00
|
|
|
if p in close_list:
|
|
|
|
close_list.remove(p)
|
2011-11-09 00:45:18 -04:00
|
|
|
|
|
|
|
def pexpect_close_all():
|
|
|
|
'''close all pexpect children'''
|
|
|
|
global close_list
|
|
|
|
for p in close_list[:]:
|
|
|
|
try:
|
2011-11-09 02:44:14 -04:00
|
|
|
p.close()
|
|
|
|
time.sleep(1)
|
2011-11-09 01:15:53 -04:00
|
|
|
p.close(Force=True)
|
2011-11-09 00:45:18 -04:00
|
|
|
except Exception:
|
|
|
|
pass
|
|
|
|
|
2011-11-09 02:44:14 -04:00
|
|
|
def start_SIL(atype, valgrind=False, wipe=False, CLI=False):
|
2011-10-30 23:50:34 -03:00
|
|
|
'''launch a SIL instance'''
|
2011-11-07 07:55:21 -04:00
|
|
|
cmd=""
|
2011-11-08 03:07:01 -04:00
|
|
|
if valgrind and os.path.exists('/usr/bin/valgrind'):
|
2011-11-07 07:55:21 -04:00
|
|
|
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)
|
2011-11-09 01:15:53 -04:00
|
|
|
pexpect_autoclose(ret)
|
2011-10-30 23:50:34 -03:00
|
|
|
ret.expect('Waiting for connection')
|
|
|
|
return ret
|
|
|
|
|
2011-11-07 07:55:21 -04:00
|
|
|
def start_MAVProxy_SIL(atype, aircraft=None, setup=False, master='tcp:127.0.0.1:5760',
|
|
|
|
options=None, logfile=sys.stdout):
|
2011-10-30 23:50:34 -03:00
|
|
|
'''launch mavproxy connected to a SIL instance'''
|
2011-11-09 00:45:18 -04:00
|
|
|
global close_list
|
2011-11-01 08:31:01 -03:00
|
|
|
MAVPROXY = reltopdir('../MAVProxy/mavproxy.py')
|
2011-11-07 07:55:21 -04:00
|
|
|
cmd = MAVPROXY + ' --master=%s' % master
|
|
|
|
if setup:
|
|
|
|
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)
|
2011-11-09 01:15:53 -04:00
|
|
|
pexpect_autoclose(ret)
|
2011-10-30 23:50:34 -03:00
|
|
|
return ret
|
|
|
|
|
|
|
|
|
2011-11-01 08:31:01 -03:00
|
|
|
def expect_setup_callback(e, callback):
|
|
|
|
'''setup a callback that is called once a second while waiting for
|
|
|
|
patterns'''
|
|
|
|
def _expect_callback(pattern, timeout=e.timeout):
|
|
|
|
tstart = time.time()
|
|
|
|
while time.time() < tstart + timeout:
|
|
|
|
try:
|
|
|
|
ret = e.expect_saved(pattern, timeout=1)
|
|
|
|
return ret
|
|
|
|
except pexpect.TIMEOUT:
|
|
|
|
e.expect_user_callback(e)
|
|
|
|
pass
|
|
|
|
raise pexpect.TIMEOUT
|
|
|
|
|
|
|
|
e.expect_user_callback = callback
|
|
|
|
e.expect_saved = e.expect
|
|
|
|
e.expect = _expect_callback
|
2011-11-07 05:12:51 -04:00
|
|
|
|
|
|
|
def mkdir_p(dir):
|
|
|
|
'''like mkdir -p'''
|
|
|
|
if not dir:
|
|
|
|
return
|
|
|
|
if dir.endswith("/"):
|
|
|
|
mkdir_p(dir[:-1])
|
|
|
|
return
|
|
|
|
if os.path.isdir(dir):
|
|
|
|
return
|
|
|
|
mkdir_p(os.path.dirname(dir))
|
|
|
|
os.mkdir(dir)
|