Browse Source

autotest: added --viewerip option

this allows you to specify an IP that will receive all MAVLink logs
and fg data for realtime viewing
mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
dafbdd1f2b
  1. 21
      Tools/autotest/arducopter.py
  2. 4
      Tools/autotest/autotest.py

21
Tools/autotest/arducopter.py

@ -275,8 +275,12 @@ def setup_rc(mavproxy): @@ -275,8 +275,12 @@ def setup_rc(mavproxy):
mavproxy.send('rc 3 1000\n')
def fly_ArduCopter():
'''fly ArduCopter in SIL'''
def fly_ArduCopter(viewerip=None):
'''fly ArduCopter in SIL
you can pass viewerip as an IP address to optionally send fg and
mavproxy packets too for local viewing of the flight in real time
'''
global expect_list, homeloc
sil = util.start_SIL('ArduCopter', wipe=True)
@ -295,12 +299,13 @@ def fly_ArduCopter(): @@ -295,12 +299,13 @@ def fly_ArduCopter():
mavproxy.expect('Loaded [0-9]+ parameters')
# reboot with new parameters
print("CLOSING")
util.pexpect_close(mavproxy)
util.pexpect_close(sil)
print("CLOSED THEM")
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:19550 --out=192.168.2.15:14550 --quadcopter --streamrate=1')
options = '--fgout=127.0.0.1:5502 --fgin=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=1'
if viewerip:
options += ' --out=%s:14550' % viewerip
mavproxy = util.start_MAVProxy_SIL('ArduCopter', options=options)
mavproxy.expect('Logging to (\S+)')
logfile = mavproxy.match.group(1)
print("LOGFILE %s" % logfile)
@ -317,8 +322,10 @@ def fly_ArduCopter(): @@ -317,8 +322,10 @@ def fly_ArduCopter():
util.expect_setup_callback(mavproxy, expect_callback)
# start hil_quad.py
hquad = pexpect.spawn(util.reltopdir('../HILTest/hil_quad.py') + ' --fgout=192.168.2.15:9123 --fgrate=200 --home=%s' % HOME_LOCATION,
logfile=sys.stdout, timeout=10)
cmd = util.reltopdir('../HILTest/hil_quad.py') + ' --fgrate=200 --home=%s' % HOME_LOCATION
if viewerip:
cmd += ' --fgout=192.168.2.15:9123'
hquad = pexpect.spawn(cmd, logfile=sys.stdout, timeout=10)
util.pexpect_autoclose(hquad)
hquad.expect('Starting at')

4
Tools/autotest/autotest.py

@ -81,6 +81,7 @@ You can get it from git://git.samba.org/tridge/UAV/HILTest.git @@ -81,6 +81,7 @@ You can get it from git://git.samba.org/tridge/UAV/HILTest.git
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')
opts, args = parser.parse_args()
@ -145,7 +146,7 @@ def run_step(step): @@ -145,7 +146,7 @@ def run_step(step):
return dump_logs('ArduCopter')
if step == 'fly.ArduCopter':
return arducopter.fly_ArduCopter()
return arducopter.fly_ArduCopter(viewerip=opts.viewerip)
if step == 'convertgpx':
return convert_gpx()
@ -264,6 +265,7 @@ try: @@ -264,6 +265,7 @@ try:
if not run_tests(steps):
sys.exit(1)
except KeyboardInterrupt:
print("INTERRUPT: Stopping child processes ....")
util.pexpect_close_all()
sys.exit(1)
except Exception:

Loading…
Cancel
Save