autotest: removed use of --nowait option

This commit is contained in:
Andrew Tridgell 2015-03-27 18:03:24 -07:00
parent 7cd7ff89fd
commit cf15b4d4fc
4 changed files with 6 additions and 6 deletions

View File

@ -83,7 +83,7 @@ def drive_APMrover2(viewerip=None, map=False):
if map:
options += ' --map'
sim_cmd = util.reltopdir('Tools/autotest/pysim/sim_rover.py') + ' --rate=200 --nowait --home=%f,%f,%u,%u' % (
sim_cmd = util.reltopdir('Tools/autotest/pysim/sim_rover.py') + ' --rate=200 --speedup=100 --home=%f,%f,%u,%u' % (
HOME.lat, HOME.lng, HOME.alt, HOME.heading)
sil = util.start_SIL('APMrover2', wipe=True)
@ -111,7 +111,7 @@ def drive_APMrover2(viewerip=None, map=False):
logfile = mavproxy.match.group(1)
print("LOGFILE %s" % logfile)
sim_cmd = util.reltopdir('Tools/autotest/pysim/sim_rover.py') + ' --rate=200 --nowait --home=%f,%f,%u,%u' % (
sim_cmd = util.reltopdir('Tools/autotest/pysim/sim_rover.py') + ' --rate=200 --speedup=100 --home=%f,%f,%u,%u' % (
HOME.lat, HOME.lng, HOME.alt, HOME.heading)
runsim = pexpect.spawn(sim_cmd, logfile=sys.stdout, timeout=10)

View File

@ -880,7 +880,7 @@ def fly_ArduCopter(viewerip=None, map=False):
if TARGET != 'sitl':
util.build_SIL('ArduCopter', target=TARGET)
sim_cmd = util.reltopdir('Tools/autotest/pysim/sim_multicopter.py') + ' --frame=%s --nowait --nowait --rate=400 --home=%f,%f,%u,%u' % (
sim_cmd = util.reltopdir('Tools/autotest/pysim/sim_multicopter.py') + ' --frame=%s --speedup=100 --rate=400 --home=%f,%f,%u,%u' % (
FRAME, HOME.lat, HOME.lng, HOME.alt, HOME.heading)
sim_cmd += ' --wind=6,45,.3'
if viewerip:
@ -1252,7 +1252,7 @@ def fly_CopterAVC(viewerip=None, map=False):
if TARGET != 'sitl':
util.build_SIL('ArduCopter', target=TARGET)
sim_cmd = util.reltopdir('Tools/autotest/pysim/sim_multicopter.py') + ' --frame=%s --rate=400 --nowait --home=%f,%f,%u,%u' % (
sim_cmd = util.reltopdir('Tools/autotest/pysim/sim_multicopter.py') + ' --frame=%s --rate=400 --speedup=100 --home=%f,%f,%u,%u' % (
FRAME, AVCHOME.lat, AVCHOME.lng, AVCHOME.alt, AVCHOME.heading)
if viewerip:
sim_cmd += ' --fgout=%s:5503' % viewerip

View File

@ -19,7 +19,7 @@ def get_default_params(atype):
# use rover simulator so SITL is not starved of input
from pymavlink import mavutil
HOME=mavutil.location(40.071374969556928,-105.22978898137808,1583.702759,246)
sim_cmd = util.reltopdir('Tools/autotest/pysim/sim_rover.py') + ' --rate=200 --nowait --home=%f,%f,%u,%u' % (
sim_cmd = util.reltopdir('Tools/autotest/pysim/sim_rover.py') + ' --rate=200 --speedup=100 --home=%f,%f,%u,%u' % (
HOME.lat, HOME.lng, HOME.alt, HOME.heading)
runsim = pexpect.spawn(sim_cmd, logfile=sys.stdout, timeout=10)

View File

@ -152,7 +152,7 @@ while True:
sim_send(a)
now = time.time()
if not opts.nowait and now < last_wall_time + scaled_frame_time:
if now < last_wall_time + scaled_frame_time:
time.sleep(last_wall_time+scaled_frame_time - now)
last_wall_time = time.time()