autotest: use builtin rover model for autotest
This commit is contained in:
parent
9dede2f0ec
commit
209896afc7
@ -83,16 +83,10 @@ def drive_APMrover2(viewerip=None, map=False):
|
|||||||
if map:
|
if map:
|
||||||
options += ' --map'
|
options += ' --map'
|
||||||
|
|
||||||
sim_cmd = util.reltopdir('Tools/autotest/pysim/sim_wrapper.py') + ' --frame=rover --rate=200 --speedup=100 --home=%f,%f,%u,%u' % (
|
home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading)
|
||||||
HOME.lat, HOME.lng, HOME.alt, HOME.heading)
|
sil = util.start_SIL('APMrover2', wipe=True, model='rover', home=home, speedup=10)
|
||||||
|
|
||||||
sil = util.start_SIL('APMrover2', wipe=True)
|
|
||||||
mavproxy = util.start_MAVProxy_SIL('APMrover2', options=options)
|
mavproxy = util.start_MAVProxy_SIL('APMrover2', options=options)
|
||||||
|
|
||||||
runsim = pexpect.spawn(sim_cmd, logfile=sys.stdout, timeout=10)
|
|
||||||
runsim.delaybeforesend = 0
|
|
||||||
runsim.expect('Starting at lat')
|
|
||||||
|
|
||||||
print("WAITING FOR PARAMETERS")
|
print("WAITING FOR PARAMETERS")
|
||||||
mavproxy.expect('Received [0-9]+ parameters')
|
mavproxy.expect('Received [0-9]+ parameters')
|
||||||
|
|
||||||
@ -103,9 +97,8 @@ def drive_APMrover2(viewerip=None, map=False):
|
|||||||
# restart with new parms
|
# restart with new parms
|
||||||
util.pexpect_close(mavproxy)
|
util.pexpect_close(mavproxy)
|
||||||
util.pexpect_close(sil)
|
util.pexpect_close(sil)
|
||||||
util.pexpect_close(runsim)
|
|
||||||
|
|
||||||
sil = util.start_SIL('APMrover2')
|
sil = util.start_SIL('APMrover2', model='rover', home=home, speedup=10)
|
||||||
mavproxy = util.start_MAVProxy_SIL('APMrover2', options=options)
|
mavproxy = util.start_MAVProxy_SIL('APMrover2', options=options)
|
||||||
mavproxy.expect('Logging to (\S+)')
|
mavproxy.expect('Logging to (\S+)')
|
||||||
logfile = mavproxy.match.group(1)
|
logfile = mavproxy.match.group(1)
|
||||||
@ -114,11 +107,6 @@ def drive_APMrover2(viewerip=None, map=False):
|
|||||||
sim_cmd = util.reltopdir('Tools/autotest/pysim/sim_wrapper.py') + ' --frame=rover --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)
|
HOME.lat, HOME.lng, HOME.alt, HOME.heading)
|
||||||
|
|
||||||
runsim = pexpect.spawn(sim_cmd, logfile=sys.stdout, timeout=10)
|
|
||||||
runsim.delaybeforesend = 0
|
|
||||||
util.pexpect_autoclose(runsim)
|
|
||||||
runsim.expect('Starting at lat')
|
|
||||||
|
|
||||||
buildlog = util.reltopdir("../buildlogs/APMrover2-test.tlog")
|
buildlog = util.reltopdir("../buildlogs/APMrover2-test.tlog")
|
||||||
print("buildlog=%s" % buildlog)
|
print("buildlog=%s" % buildlog)
|
||||||
if os.path.exists(buildlog):
|
if os.path.exists(buildlog):
|
||||||
@ -133,7 +121,7 @@ def drive_APMrover2(viewerip=None, map=False):
|
|||||||
util.expect_setup_callback(mavproxy, expect_callback)
|
util.expect_setup_callback(mavproxy, expect_callback)
|
||||||
|
|
||||||
expect_list_clear()
|
expect_list_clear()
|
||||||
expect_list_extend([runsim, sil, mavproxy])
|
expect_list_extend([sil, mavproxy])
|
||||||
|
|
||||||
print("Started simulator")
|
print("Started simulator")
|
||||||
|
|
||||||
@ -176,7 +164,6 @@ def drive_APMrover2(viewerip=None, map=False):
|
|||||||
mav.close()
|
mav.close()
|
||||||
util.pexpect_close(mavproxy)
|
util.pexpect_close(mavproxy)
|
||||||
util.pexpect_close(sil)
|
util.pexpect_close(sil)
|
||||||
util.pexpect_close(runsim)
|
|
||||||
|
|
||||||
if os.path.exists('APMrover2-valgrind.log'):
|
if os.path.exists('APMrover2-valgrind.log'):
|
||||||
os.chmod('APMrover2-valgrind.log', 0644)
|
os.chmod('APMrover2-valgrind.log', 0644)
|
||||||
|
@ -144,6 +144,7 @@ parser.add_option("--viewerip", default=None, help='IP address to send MAVLink a
|
|||||||
parser.add_option("--map", action='store_true', default=False, help='show map')
|
parser.add_option("--map", action='store_true', default=False, help='show map')
|
||||||
parser.add_option("--experimental", default=False, action='store_true', help='enable experimental tests')
|
parser.add_option("--experimental", default=False, action='store_true', help='enable experimental tests')
|
||||||
parser.add_option("--timeout", default=3000, type='int', help='maximum runtime in seconds')
|
parser.add_option("--timeout", default=3000, type='int', help='maximum runtime in seconds')
|
||||||
|
parser.add_option("-j", default=1, type='int', help='build CPUs')
|
||||||
|
|
||||||
opts, args = parser.parse_args()
|
opts, args = parser.parse_args()
|
||||||
|
|
||||||
@ -201,13 +202,13 @@ def run_step(step):
|
|||||||
return test_prerequisites()
|
return test_prerequisites()
|
||||||
|
|
||||||
if step == 'build.ArduPlane':
|
if step == 'build.ArduPlane':
|
||||||
return util.build_SIL('ArduPlane')
|
return util.build_SIL('ArduPlane', j=opts.j)
|
||||||
|
|
||||||
if step == 'build.APMrover2':
|
if step == 'build.APMrover2':
|
||||||
return util.build_SIL('APMrover2')
|
return util.build_SIL('APMrover2', j=opts.j)
|
||||||
|
|
||||||
if step == 'build.ArduCopter':
|
if step == 'build.ArduCopter':
|
||||||
return util.build_SIL('ArduCopter')
|
return util.build_SIL('ArduCopter', j=opts.j)
|
||||||
|
|
||||||
if step == 'defaults.ArduPlane':
|
if step == 'defaults.ArduPlane':
|
||||||
return get_default_params('ArduPlane')
|
return get_default_params('ArduPlane')
|
||||||
|
@ -58,12 +58,12 @@ def deltree(path):
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
def build_SIL(atype, target='sitl'):
|
def build_SIL(atype, target='sitl', j=1):
|
||||||
'''build desktop SIL'''
|
'''build desktop SIL'''
|
||||||
run_cmd("make clean",
|
run_cmd("make clean",
|
||||||
dir=reltopdir(atype),
|
dir=reltopdir(atype),
|
||||||
checkfail=True)
|
checkfail=True)
|
||||||
run_cmd("make %s" % target,
|
run_cmd("make -j%u %s" % (j, target),
|
||||||
dir=reltopdir(atype),
|
dir=reltopdir(atype),
|
||||||
checkfail=True)
|
checkfail=True)
|
||||||
return True
|
return True
|
||||||
@ -105,7 +105,7 @@ def pexpect_drain(p):
|
|||||||
except pexpect.TIMEOUT:
|
except pexpect.TIMEOUT:
|
||||||
pass
|
pass
|
||||||
|
|
||||||
def start_SIL(atype, valgrind=False, wipe=False, height=None, synthetic_clock=True):
|
def start_SIL(atype, valgrind=False, wipe=False, height=None, synthetic_clock=True, home=None, model=None, speedup=1):
|
||||||
'''launch a SIL instance'''
|
'''launch a SIL instance'''
|
||||||
import pexpect
|
import pexpect
|
||||||
cmd=""
|
cmd=""
|
||||||
@ -121,6 +121,12 @@ def start_SIL(atype, valgrind=False, wipe=False, height=None, synthetic_clock=Tr
|
|||||||
cmd += ' -H %u' % height
|
cmd += ' -H %u' % height
|
||||||
if synthetic_clock:
|
if synthetic_clock:
|
||||||
cmd += ' -S'
|
cmd += ' -S'
|
||||||
|
if home is not None:
|
||||||
|
cmd += ' --home=%s' % home
|
||||||
|
if model is not None:
|
||||||
|
cmd += ' --model=%s' % model
|
||||||
|
if speedup != 1:
|
||||||
|
cmd += ' --speedup=%f' % speedup
|
||||||
ret = pexpect.spawn(cmd, logfile=sys.stdout, timeout=5)
|
ret = pexpect.spawn(cmd, logfile=sys.stdout, timeout=5)
|
||||||
ret.delaybeforesend = 0
|
ret.delaybeforesend = 0
|
||||||
pexpect_autoclose(ret)
|
pexpect_autoclose(ret)
|
||||||
|
Loading…
Reference in New Issue
Block a user