autotest: run the sim at 200Hz

This commit is contained in:
Andrew Tridgell 2011-11-10 12:46:51 +11:00
parent b25ad4e61f
commit d2a8107b47
2 changed files with 3 additions and 2 deletions

View File

@ -301,7 +301,7 @@ 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 --home=%s' % HOME_LOCATION,
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)
util.pexpect_autoclose(hquad)
hquad.expect('Starting at')

View File

@ -106,11 +106,12 @@ def start_SIL(atype, valgrind=False, wipe=False, CLI=False):
return ret
def start_MAVProxy_SIL(atype, aircraft=None, setup=False, master='tcp:127.0.0.1:5760',
fgrate=200,
options=None, logfile=sys.stdout):
'''launch mavproxy connected to a SIL instance'''
global close_list
MAVPROXY = reltopdir('../MAVProxy/mavproxy.py')
cmd = MAVPROXY + ' --master=%s' % master
cmd = MAVPROXY + ' --master=%s --fgrate=%u' % (master, fgrate)
if setup:
cmd += ' --setup'
if aircraft is None: