diff --git a/Tools/autotest/apmrover2.py b/Tools/autotest/apmrover2.py index 0262d07adb..c944a21564 100644 --- a/Tools/autotest/apmrover2.py +++ b/Tools/autotest/apmrover2.py @@ -68,7 +68,7 @@ def drive_mission(mavproxy, mav, filename): return True -def drive_APMrover2(viewerip=None): +def drive_APMrover2(viewerip=None, map=False): '''drive APMrover2 in SIL you can pass viewerip as an IP address to optionally send fg and @@ -79,6 +79,8 @@ def drive_APMrover2(viewerip=None): options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --streamrate=10' if viewerip: options += " --out=%s:14550" % viewerip + if map: + options += ' --map --console' sil = util.start_SIL('APMrover2', wipe=True) mavproxy = util.start_MAVProxy_SIL('APMrover2', options=options) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 04157ae49d..62bc7fe05d 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -340,7 +340,7 @@ def setup_rc(mavproxy): mavproxy.send('rc 3 1000\n') -def fly_ArduCopter(viewerip=None): +def fly_ArduCopter(viewerip=None, map=False): '''fly ArduCopter in SIL you can pass viewerip as an IP address to optionally send fg and @@ -377,6 +377,8 @@ def fly_ArduCopter(viewerip=None): options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=5' if viewerip: options += ' --out=%s:14550' % viewerip + if map: + options += ' --map --console' mavproxy = util.start_MAVProxy_SIL('ArduCopter', options=options) mavproxy.expect('Logging to (\S+)') logfile = mavproxy.match.group(1) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 1f3ea6ecac..627ecb980b 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -216,7 +216,7 @@ def fly_mission(mavproxy, mav, filename, height_accuracy=-1, target_altitude=Non return True -def fly_ArduPlane(viewerip=None): +def fly_ArduPlane(viewerip=None, map=False): '''fly ArduPlane in SIL you can pass viewerip as an IP address to optionally send fg and @@ -227,6 +227,8 @@ def fly_ArduPlane(viewerip=None): options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --streamrate=10' if viewerip: options += " --out=%s:14550" % viewerip + if map: + options += ' --map --console' sil = util.start_SIL('ArduPlane', wipe=True) mavproxy = util.start_MAVProxy_SIL('ArduPlane', options=options) diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index 1a75374508..3ee4eb5018 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -147,6 +147,7 @@ parser = optparse.OptionParser("autotest") parser.add_option("--skip", type='string', default='', help='list of steps to skip (comma separated)') parser.add_option("--list", action='store_true', default=False, help='list the available steps') parser.add_option("--viewerip", default=None, help='IP address to send MAVLink and fg packets to') +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') @@ -252,13 +253,13 @@ def run_step(step): return dump_logs('APMrover2') if step == 'fly.ArduCopter': - return arducopter.fly_ArduCopter(viewerip=opts.viewerip) + return arducopter.fly_ArduCopter(viewerip=opts.viewerip, map=opts.map) if step == 'fly.ArduPlane': - return arduplane.fly_ArduPlane(viewerip=opts.viewerip) + return arduplane.fly_ArduPlane(viewerip=opts.viewerip, map=opts.map) if step == 'drive.APMrover2': - return apmrover2.drive_APMrover2(viewerip=opts.viewerip) + return apmrover2.drive_APMrover2(viewerip=opts.viewerip, map=opts.map) if step == 'build.All': return build_all()