Tools: convert autotest build.X and fly.X to use waf build system

This commit is contained in:
Peter Barker 2016-05-22 01:19:50 +10:00 committed by Lucas De Marchi
parent 9933069679
commit 7b86a05722
6 changed files with 114 additions and 66 deletions

View File

@ -79,7 +79,7 @@ def drive_mission(mavproxy, mav, filename):
return True
def drive_APMrover2(viewerip=None, map=False, valgrind=False):
def drive_APMrover2(binary, viewerip=None, map=False, valgrind=False):
'''drive APMrover2 in SIL
you can pass viewerip as an IP address to optionally send fg and
@ -94,7 +94,7 @@ def drive_APMrover2(viewerip=None, map=False, valgrind=False):
options += ' --map'
home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading)
sil = util.start_SIL('APMrover2', wipe=True, model='rover', home=home, speedup=10)
sil = util.start_SIL(binary, wipe=True, model='rover', home=home, speedup=10)
mavproxy = util.start_MAVProxy_SIL('APMrover2', options=options)
print("WAITING FOR PARAMETERS")
@ -108,7 +108,7 @@ def drive_APMrover2(viewerip=None, map=False, valgrind=False):
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
sil = util.start_SIL('APMrover2', model='rover', home=home, speedup=10, valgrind=valgrind)
sil = util.start_SIL(binary, model='rover', home=home, speedup=10, valgrind=valgrind)
mavproxy = util.start_MAVProxy_SIL('APMrover2', options=options)
mavproxy.expect('Telemetry log: (\S+)')
logfile = mavproxy.match.group(1)

View File

@ -908,7 +908,7 @@ def setup_rc(mavproxy):
# zero throttle
mavproxy.send('rc 3 1000\n')
def fly_ArduCopter(viewerip=None, map=False, valgrind=False):
def fly_ArduCopter(binary, viewerip=None, map=False, valgrind=False):
'''fly ArduCopter in SIL
you can pass viewerip as an IP address to optionally send fg and
@ -917,10 +917,10 @@ def fly_ArduCopter(viewerip=None, map=False, valgrind=False):
global homeloc
if TARGET != 'sitl':
util.build_SIL('ArduCopter', target=TARGET)
util.build_SIL('bin/arducopter-quad', target=TARGET)
home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading)
sil = util.start_SIL('ArduCopter', wipe=True, model='+', home=home, speedup=speedup_default)
sil = util.start_SIL(binary, wipe=True, model='+', home=home, speedup=speedup_default)
mavproxy = util.start_MAVProxy_SIL('ArduCopter', options='--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter')
mavproxy.expect('Received [0-9]+ parameters')
@ -932,7 +932,7 @@ def fly_ArduCopter(viewerip=None, map=False, valgrind=False):
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
sil = util.start_SIL('ArduCopter', model='+', home=home, speedup=speedup_default, valgrind=valgrind)
sil = util.start_SIL(binary, model='+', home=home, speedup=speedup_default, valgrind=valgrind)
options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=5'
if viewerip:
options += ' --out=%s:14550' % viewerip
@ -1258,16 +1258,13 @@ def fly_ArduCopter(viewerip=None, map=False, valgrind=False):
return True
def fly_CopterAVC(viewerip=None, map=False, valgrind=False):
def fly_CopterAVC(binary, viewerip=None, map=False, valgrind=False):
'''fly ArduCopter in SIL for AVC2013 mission
'''
global homeloc
if TARGET != 'sitl':
util.build_SIL('ArduCopter', target=TARGET)
home = "%f,%f,%u,%u" % (AVCHOME.lat, AVCHOME.lng, AVCHOME.alt, AVCHOME.heading)
sil = util.start_SIL('ArduCopter', wipe=True, model='heli', home=home, speedup=speedup_default)
sil = util.start_SIL(binary, wipe=True, model='heli', home=home, speedup=speedup_default)
mavproxy = util.start_MAVProxy_SIL('ArduCopter', options='--sitl=127.0.0.1:5501 --out=127.0.0.1:19550')
mavproxy.expect('Received [0-9]+ parameters')
@ -1279,7 +1276,7 @@ def fly_CopterAVC(viewerip=None, map=False, valgrind=False):
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
sil = util.start_SIL('ArduCopter', model='heli', home=home, speedup=speedup_default, valgrind=valgrind)
sil = util.start_SIL(binary, model='heli', home=home, speedup=speedup_default, valgrind=valgrind)
options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --streamrate=5'
if viewerip:
options += ' --out=%s:14550' % viewerip

View File

@ -426,7 +426,7 @@ def fly_mission(mavproxy, mav, filename, height_accuracy=-1, target_altitude=Non
return True
def fly_ArduPlane(viewerip=None, map=False, valgrind=False):
def fly_ArduPlane(binary, viewerip=None, map=False, valgrind=False):
'''fly ArduPlane in SIL
you can pass viewerip as an IP address to optionally send fg and
@ -440,7 +440,7 @@ def fly_ArduPlane(viewerip=None, map=False, valgrind=False):
if map:
options += ' --map'
sil = util.start_SIL('ArduPlane', wipe=True, model='jsbsim', home=HOME_LOCATION, speedup=10)
sil = util.start_SIL(binary, wipe=True, model='jsbsim', home=HOME_LOCATION, speedup=10)
print("Starting MAVProxy")
mavproxy = util.start_MAVProxy_SIL('ArduPlane', options=options)
util.expect_setup_callback(mavproxy, expect_callback)
@ -458,7 +458,7 @@ def fly_ArduPlane(viewerip=None, map=False, valgrind=False):
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
sil = util.start_SIL('ArduPlane', model='jsbsim', home=HOME_LOCATION, speedup=10, valgrind=valgrind)
sil = util.start_SIL(binary, model='jsbsim', home=HOME_LOCATION, speedup=10, valgrind=valgrind)
mavproxy = util.start_MAVProxy_SIL('ArduPlane', options=options)
mavproxy.expect('Telemetry log: (\S+)')
logfile = mavproxy.match.group(1)

View File

@ -13,19 +13,19 @@ os.environ['PYTHONUNBUFFERED'] = '1'
os.putenv('TMPDIR', util.reltopdir('tmp'))
def get_default_params(atype):
def get_default_params(atype, binary):
'''get default parameters'''
# use rover simulator so SITL is not starved of input
from pymavlink import mavutil
HOME=mavutil.location(40.071374969556928,-105.22978898137808,1583.702759,246)
if atype in ['APMrover2', 'ArduPlane']:
frame = 'rover'
if binary.find("plane") != -1 or binary.find("rover") != -1:
frame = "rover"
else:
frame = '+'
frame = "+"
home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading)
sil = util.start_SIL(atype, wipe=True, model=frame, home=home, speedup=10)
sil = util.start_SIL(binary, wipe=True, model=frame, home=home, speedup=10)
mavproxy = util.start_MAVProxy_SIL(atype)
print("Dumping defaults")
idx = mavproxy.expect(['Please Run Setup', 'Saved [0-9]+ parameters to (\S+)'])
@ -33,7 +33,7 @@ def get_default_params(atype):
# we need to restart it after eeprom erase
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
sil = util.start_SIL(atype, model=frame, home=home, speedup=10)
sil = util.start_SIL(binary, model=frame, home=home, speedup=10)
mavproxy = util.start_MAVProxy_SIL(atype)
idx = mavproxy.expect('Saved [0-9]+ parameters to (\S+)')
parmfile = mavproxy.match.group(1)
@ -139,7 +139,8 @@ parser.add_option("--map", action='store_true', default=False, help='show map')
parser.add_option("--experimental", default=False, action='store_true', help='enable experimental tests')
parser.add_option("--timeout", default=3000, type='int', help='maximum runtime in seconds')
parser.add_option("--valgrind", default=False, action='store_true', help='run ArduPilot binaries under valgrind')
parser.add_option("-j", default=1, type='int', help='build CPUs')
parser.add_option("--debug", default=False, action='store_true', help='make built binaries debug binaries')
parser.add_option("-j", default=None, type='int', help='build CPUs')
opts, args = parser.parse_args()
@ -192,6 +193,36 @@ def skip_step(step):
return True
return False
def binary_path(step, debug=False):
if step.find("ArduCopter") != -1:
binary_name = "arducopter-quad"
elif step.find("ArduPlane") != -1:
binary_name = "arduplane"
elif step.find("APMrover2") != -1:
binary_name = "ardurover"
elif step.find("AntennaTracker") != -1:
binary_name = "antennatracker"
elif step.find("CopterAVC") != -1:
binary_name = "arducopter-heli"
elif step.find("QuadPlane") != -1:
binary_name = "arduplane"
else:
raise(ValueError("Unable to determine binary name for step %s" % (step,)))
if debug:
binary_basedir = "sitl-debug"
else:
binary_basedir = "sitl"
binary = util.reltopdir(os.path.join('build', binary_basedir, 'bin', binary_name))
if not os.path.exists(binary):
if os.path.exists(binary + ".exe"):
binary_path += ".exe"
else:
raise ValueError("Binary (%s) does not exist" % (binary,))
return binary
def run_step(step):
'''run one step'''
@ -202,43 +233,45 @@ def run_step(step):
return test_prerequisites()
if step == 'build.ArduPlane':
return util.build_SIL('ArduPlane', j=opts.j)
return util.build_SIL('bin/arduplane', j=opts.j, debug=opts.debug)
if step == 'build.APMrover2':
return util.build_SIL('APMrover2', j=opts.j)
return util.build_SIL('bin/ardurover', j=opts.j, debug=opts.debug)
if step == 'build.ArduCopter':
return util.build_SIL('ArduCopter', j=opts.j)
return util.build_SIL('bin/arducopter-quad', j=opts.j, debug=opts.debug)
if step == 'build.AntennaTracker':
return util.build_SIL('AntennaTracker', j=opts.j)
return util.build_SIL('bin/antennatracker', j=opts.j, debug=opts.debug)
if step == 'build.Helicopter':
return util.build_SIL('ArduCopter', target='sitl-heli', j=opts.j)
return util.build_SIL('bin/arducopter-heli', j=opts.j, debug=opts.debug)
binary = binary_path(step, debug=opts.debug)
if step == 'defaults.ArduPlane':
return get_default_params('ArduPlane')
return get_default_params('ArduPlane', binary)
if step == 'defaults.ArduCopter':
return get_default_params('ArduCopter')
return get_default_params('ArduCopter', binary)
if step == 'defaults.APMrover2':
return get_default_params('APMrover2')
return get_default_params('APMrover2', binary)
if step == 'fly.ArduCopter':
return arducopter.fly_ArduCopter(viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind)
return arducopter.fly_ArduCopter(binary, viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind)
if step == 'fly.CopterAVC':
return arducopter.fly_CopterAVC(viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind)
return arducopter.fly_CopterAVC(binary, viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind)
if step == 'fly.ArduPlane':
return arduplane.fly_ArduPlane(viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind)
return arduplane.fly_ArduPlane(binary, viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind)
if step == 'fly.QuadPlane':
return quadplane.fly_QuadPlane(viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind)
return quadplane.fly_QuadPlane(binary, viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind)
if step == 'drive.APMrover2':
return apmrover2.drive_APMrover2(viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind)
return apmrover2.drive_APMrover2(binary, viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind)
if step == 'build.All':
return build_all()

View File

@ -34,16 +34,20 @@ def reltopdir(path):
return os.path.normpath(os.path.join(topdir(), path))
def run_cmd(cmd, dir=".", show=False, output=False, checkfail=True):
def run_cmd(cmd, dir=".", show=True, output=False, checkfail=True):
'''run a shell command'''
shell = False
if not isinstance(cmd, list):
cmd = [cmd]
shell = True
if show:
print("Running: '%s' in '%s'" % (cmd, dir))
print("Running: (%s) in (%s)" % (cmd_as_shell(cmd), dir,))
if output:
return Popen([cmd], shell=True, stdout=PIPE, cwd=dir).communicate()[0]
return Popen(cmd, shell=shell, stdout=PIPE, cwd=dir).communicate()[0]
elif checkfail:
return check_call(cmd, shell=True, cwd=dir)
return check_call(cmd, shell=shell, cwd=dir)
else:
return call(cmd, shell=True, cwd=dir)
return call(cmd, shell=shell, cwd=dir)
def rmfile(path):
'''remove a file if it exists'''
@ -57,15 +61,26 @@ def deltree(path):
run_cmd('rm -rf %s' % path)
def relwaf():
return "./modules/waf/waf-light"
def build_SIL(atype, target='sitl', j=1):
def build_SIL(build_target, j=None, debug=False):
'''build desktop SIL'''
run_cmd("make clean",
dir=reltopdir(atype),
checkfail=True)
run_cmd("make -j%u %s" % (j, target),
dir=reltopdir(atype),
checkfail=True)
# first configure
cmd_configure = [relwaf(), "configure", "--board", 'sitl']
if debug:
cmd_configure.append('--debug')
if j is not None:
cmd_configure.extend(['-j', str(j)])
run_cmd(cmd_configure, dir=topdir(), checkfail=True)
# then clean
run_cmd([relwaf(), "clean"], dir=topdir(), checkfail=True)
# then build
cmd_make = [relwaf(), "build", "--target", build_target]
run_cmd(cmd_make, dir=topdir(), checkfail=True, show=True)
return True
# list of pexpect children to close on exit
@ -105,35 +120,38 @@ def pexpect_drain(p):
except pexpect.TIMEOUT:
pass
def start_SIL(atype, valgrind=False, gdb=False, wipe=False, synthetic_clock=True, home=None, model=None, speedup=1, defaults_file=None):
def cmd_as_shell(cmd):
return (" ".join([ '"%s"' % x for x in cmd ]))
def start_SIL(binary, valgrind=False, gdb=False, wipe=False, synthetic_clock=True, home=None, model=None, speedup=1, defaults_file=None):
'''launch a SIL instance'''
import pexpect
cmd=""
cmd=[]
if valgrind and os.path.exists('/usr/bin/valgrind'):
cmd += 'valgrind -q --log-file=%s-valgrind.log ' % atype
cmd.extend(['valgrind', '-q', '--log-file', '%s-valgrind.log' % atype])
if gdb:
f = open("/tmp/x.gdb", "w")
f.write("r\n");
f.close()
cmd += 'xterm -e gdb -x /tmp/x.gdb --args '
executable = reltopdir('tmp/%s.build/%s.elf' % (atype, atype))
if not os.path.exists(executable):
executable = '/tmp/%s.build/%s.elf' % (atype, atype)
cmd += executable
cmd.extend(['xterm', '-e', 'gdb', '-x', '/tmp/x.gdb', '--args'])
cmd.append(binary)
if wipe:
cmd += ' -w'
cmd.append('-w')
if synthetic_clock:
cmd += ' -S'
cmd.append('-S')
if home is not None:
cmd += ' --home=%s' % home
cmd.extend(['--home', home])
if model is not None:
cmd += ' --model=%s' % model
cmd.extend(['--model', model])
if speedup != 1:
cmd += ' --speedup=%f' % speedup
cmd.extend(['--speedup', str(speedup)])
if defaults_file is not None:
cmd += ' --defaults=%s' % defaults_file
print("Running: %s" % cmd)
ret = pexpect.spawn(cmd, logfile=sys.stdout, timeout=5)
cmd.extend(['--defaults', defaults_file])
print("Running: %s" % cmd_as_shell(cmd))
first = cmd[0]
rest = cmd[1:]
ret = pexpect.spawn(first, rest, logfile=sys.stdout, timeout=5)
ret.delaybeforesend = 0
pexpect_autoclose(ret)
# give time for parameters to properly setup

View File

@ -40,7 +40,7 @@ def fly_mission(mavproxy, mav, filename, fence, height_accuracy=-1):
return True
def fly_QuadPlane(viewerip=None, map=False, valgrind=False):
def fly_QuadPlane(binary, viewerip=None, map=False, valgrind=False):
'''fly QuadPlane in SIL
you can pass viewerip as an IP address to optionally send fg and
@ -54,7 +54,7 @@ def fly_QuadPlane(viewerip=None, map=False, valgrind=False):
if map:
options += ' --map'
sil = util.start_SIL('ArduPlane', model='quadplane', wipe=True, home=HOME_LOCATION, speedup=10,
sil = util.start_SIL(binary, model='quadplane', wipe=True, home=HOME_LOCATION, speedup=10,
defaults_file=os.path.join(testdir, 'quadplane.parm'), valgrind=valgrind)
mavproxy = util.start_MAVProxy_SIL('QuadPlane', options=options)
mavproxy.expect('Telemetry log: (\S+)')