autotest: enable new SITL emulation code

this enables the register level SITL code
This commit is contained in:
Andrew Tridgell 2011-11-26 14:45:18 +11:00 committed by Pat Hickey
parent 5fd04e0c23
commit c64a5f354e
3 changed files with 19 additions and 16 deletions

View File

@ -9,7 +9,7 @@ testdir=os.path.dirname(os.path.realpath(__file__))
sys.path.insert(0, util.reltopdir('../pymavlink')) sys.path.insert(0, util.reltopdir('../pymavlink'))
import mavutil, mavwp import mavutil, mavwp
HOME_LOCATION='-35.362938,149.165085,584,270' HOME=location(-35.362938,149.165085,584,270)
homeloc = None homeloc = None
num_wp = 0 num_wp = 0
@ -231,6 +231,11 @@ def fly_ArduCopter(viewerip=None):
''' '''
global expect_list, homeloc global expect_list, homeloc
hquad_cmd = util.reltopdir('../HILTest/hil_quad.py') + ' --fgrate=200 --home=%f,%f,%u,%u' % (
HOME.lat, HOME.lng, HOME.alt, HOME.heading)
if viewerip:
hquad_cmd += ' --fgout=192.168.2.15:9123'
sil = util.start_SIL('ArduCopter', wipe=True) sil = util.start_SIL('ArduCopter', wipe=True)
mavproxy = util.start_MAVProxy_SIL('ArduCopter') mavproxy = util.start_MAVProxy_SIL('ArduCopter')
mavproxy.expect('Please Run Setup') mavproxy.expect('Please Run Setup')
@ -239,7 +244,7 @@ def fly_ArduCopter(viewerip=None):
util.pexpect_close(mavproxy) util.pexpect_close(mavproxy)
util.pexpect_close(sil) util.pexpect_close(sil)
sil = util.start_SIL('ArduCopter') 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 --quadcopter') 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') mavproxy.expect('Received [0-9]+ parameters')
# setup test parameters # setup test parameters
@ -249,8 +254,11 @@ def fly_ArduCopter(viewerip=None):
# reboot with new parameters # reboot with new parameters
util.pexpect_close(mavproxy) util.pexpect_close(mavproxy)
util.pexpect_close(sil) util.pexpect_close(sil)
sil = util.start_SIL('ArduCopter')
options = '--fgout=127.0.0.1:5502 --fgin=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=1' sil = util.start_SIL('ArduCopter', height=HOME.alt)
hquad = pexpect.spawn(hquad_cmd, logfile=sys.stdout, timeout=10)
util.pexpect_autoclose(hquad)
options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=1'
if viewerip: if viewerip:
options += ' --out=%s:14550' % viewerip options += ' --out=%s:14550' % viewerip
mavproxy = util.start_MAVProxy_SIL('ArduCopter', options=options) mavproxy = util.start_MAVProxy_SIL('ArduCopter', options=options)
@ -264,19 +272,11 @@ def fly_ArduCopter(viewerip=None):
os.unlink(buildlog) os.unlink(buildlog)
os.link(logfile, buildlog) os.link(logfile, buildlog)
mavproxy.expect("Ready to FLY")
mavproxy.expect('Received [0-9]+ parameters') mavproxy.expect('Received [0-9]+ parameters')
mavproxy.expect("Ready to FLY")
util.expect_setup_callback(mavproxy, expect_callback) util.expect_setup_callback(mavproxy, expect_callback)
# start hil_quad.py
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')
expect_list.extend([hquad, sil, mavproxy]) expect_list.extend([hquad, sil, mavproxy])
# get a mavlink connection going # get a mavlink connection going

View File

@ -30,10 +30,11 @@ def expect_callback(e):
class location(object): class location(object):
'''represent a GPS coordinate''' '''represent a GPS coordinate'''
def __init__(self, lat, lng, alt=0): def __init__(self, lat, lng, alt=0, heading=0):
self.lat = lat self.lat = lat
self.lng = lng self.lng = lng
self.alt = alt self.alt = alt
self.heading = heading
def __str__(self): def __str__(self):
return "lat=%.6f,lon=%.6f,alt=%.1f" % (self.lat, self.lng, self.alt) return "lat=%.6f,lon=%.6f,alt=%.1f" % (self.lat, self.lng, self.alt)

View File

@ -44,7 +44,7 @@ def deltree(path):
def build_SIL(atype): def build_SIL(atype):
'''build desktop SIL''' '''build desktop SIL'''
run_cmd("make -f ../libraries/Desktop/Makefile.desktop clean hil", run_cmd("make -f ../libraries/Desktop/Makefile.desktop clean all",
dir=reltopdir(atype), dir=reltopdir(atype),
checkfail=True) checkfail=True)
return True return True
@ -95,7 +95,7 @@ def pexpect_close_all():
for p in close_list[:]: for p in close_list[:]:
pexpect_close(p) pexpect_close(p)
def start_SIL(atype, valgrind=False, wipe=False, CLI=False): def start_SIL(atype, valgrind=False, wipe=False, CLI=False, height=None):
'''launch a SIL instance''' '''launch a SIL instance'''
cmd="" cmd=""
if valgrind and os.path.exists('/usr/bin/valgrind'): if valgrind and os.path.exists('/usr/bin/valgrind'):
@ -105,6 +105,8 @@ def start_SIL(atype, valgrind=False, wipe=False, CLI=False):
cmd += ' -w' cmd += ' -w'
if CLI: if CLI:
cmd += ' -s' cmd += ' -s'
if height is not None:
cmd += ' -H %u' % height
ret = pexpect.spawn(cmd, logfile=sys.stdout, timeout=5) ret = pexpect.spawn(cmd, logfile=sys.stdout, timeout=5)
pexpect_autoclose(ret) pexpect_autoclose(ret)
ret.expect('Waiting for connection') ret.expect('Waiting for connection')