autotest: fixed extraction of defaults

This commit is contained in:
Andrew Tridgell 2015-04-20 15:09:31 +10:00
parent 8f09ee077c
commit 5f8c05b712
3 changed files with 3 additions and 4 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 --speedup=100 --home=%f,%f,%u,%u' % (
sim_cmd = util.reltopdir('Tools/autotest/pysim/sim_wrapper.py') + ' --frame=rover --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 --speedup=100 --home=%f,%f,%u,%u' % (
sim_cmd = util.reltopdir('Tools/autotest/pysim/sim_wrapper.py') + ' --frame=rover --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

@ -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 --speedup=100 --home=%f,%f,%u,%u' % (
sim_cmd = util.reltopdir('Tools/autotest/pysim/sim_wrapper.py') + ' --frame=rover --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

@ -150,7 +150,6 @@ kill_tasks()
killall -q JSBSim lt-JSBSim ArduPlane.elf ArduCopter.elf APMrover2.elf AntennaTracker.elf
pkill -f runsim.py
pkill -f sim_tracker.py
pkill -f sim_rover.py
pkill -f sim_wrapper.py
}
}