Tools: add valgrind option to autotest.py

This commit is contained in:
Peter Barker 2016-04-11 18:05:39 +10:00
parent f2c63e24c5
commit 8774f15b9a
4 changed files with 12 additions and 11 deletions

View File

@ -79,7 +79,7 @@ def drive_mission(mavproxy, mav, filename):
return True
def drive_APMrover2(viewerip=None, map=False):
def drive_APMrover2(viewerip=None, map=False, valgrind=False):
'''drive APMrover2 in SIL
you can pass viewerip as an IP address to optionally send fg and
@ -108,7 +108,7 @@ def drive_APMrover2(viewerip=None, map=False):
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
sil = util.start_SIL('APMrover2', model='rover', home=home, speedup=10)
sil = util.start_SIL('APMrover2', 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

@ -904,7 +904,7 @@ def setup_rc(mavproxy):
# zero throttle
mavproxy.send('rc 3 1000\n')
def fly_ArduCopter(viewerip=None, map=False):
def fly_ArduCopter(viewerip=None, map=False, valgrind=False):
'''fly ArduCopter in SIL
you can pass viewerip as an IP address to optionally send fg and
@ -928,7 +928,7 @@ def fly_ArduCopter(viewerip=None, map=False):
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
sil = util.start_SIL('ArduCopter', model='+', home=home, speedup=speedup_default)
sil = util.start_SIL('ArduCopter', 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

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):
def fly_ArduPlane(viewerip=None, map=False, valgrind=False):
'''fly ArduPlane in SIL
you can pass viewerip as an IP address to optionally send fg and
@ -458,7 +458,7 @@ def fly_ArduPlane(viewerip=None, map=False):
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
sil = util.start_SIL('ArduPlane', model='jsbsim', home=HOME_LOCATION, speedup=10)
sil = util.start_SIL('ArduPlane', 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

@ -138,6 +138,7 @@ parser.add_option("--viewerip", default=None, help='IP address to send MAVLink a
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')
opts, args = parser.parse_args()
@ -225,19 +226,19 @@ def run_step(step):
return get_default_params('APMrover2')
if step == 'fly.ArduCopter':
return arducopter.fly_ArduCopter(viewerip=opts.viewerip, map=opts.map)
return arducopter.fly_ArduCopter(viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind)
if step == 'fly.CopterAVC':
return arducopter.fly_CopterAVC(viewerip=opts.viewerip, map=opts.map)
return arducopter.fly_CopterAVC(viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind)
if step == 'fly.ArduPlane':
return arduplane.fly_ArduPlane(viewerip=opts.viewerip, map=opts.map)
return arduplane.fly_ArduPlane(viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind)
if step == 'fly.QuadPlane':
return quadplane.fly_QuadPlane(viewerip=opts.viewerip, map=opts.map)
return quadplane.fly_QuadPlane(viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind)
if step == 'drive.APMrover2':
return apmrover2.drive_APMrover2(viewerip=opts.viewerip, map=opts.map)
return apmrover2.drive_APMrover2(viewerip=opts.viewerip, map=opts.map, valgrind=opts.valgrind)
if step == 'build.All':
return build_all()