mirror of https://github.com/ArduPilot/ardupilot
autotest: use internal copter sim for autotest
This commit is contained in:
parent
d5b51f2129
commit
fe536a4b89
|
@ -104,9 +104,6 @@ def drive_APMrover2(viewerip=None, map=False):
|
||||||
logfile = mavproxy.match.group(1)
|
logfile = mavproxy.match.group(1)
|
||||||
print("LOGFILE %s" % logfile)
|
print("LOGFILE %s" % logfile)
|
||||||
|
|
||||||
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)
|
|
||||||
|
|
||||||
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):
|
||||||
|
|
|
@ -1271,7 +1271,7 @@ def fly_CopterAVC(viewerip=None, map=False):
|
||||||
util.pexpect_close(mavproxy)
|
util.pexpect_close(mavproxy)
|
||||||
util.pexpect_close(sil)
|
util.pexpect_close(sil)
|
||||||
|
|
||||||
sil = util.start_SIL('ArduCopter', height=HOME.alt)
|
sil = util.start_SIL('ArduCopter', height=HOME.alt, model='+', home=home, speedup=10)
|
||||||
options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=5'
|
options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=5'
|
||||||
if viewerip:
|
if viewerip:
|
||||||
options += ' --out=%s:14550' % viewerip
|
options += ' --out=%s:14550' % viewerip
|
||||||
|
|
|
@ -22,15 +22,10 @@ def get_default_params(atype):
|
||||||
if atype in ['APMrover2', 'ArduPlane']:
|
if atype in ['APMrover2', 'ArduPlane']:
|
||||||
frame = 'rover'
|
frame = 'rover'
|
||||||
else:
|
else:
|
||||||
frame = 'quad'
|
frame = '+'
|
||||||
sim_cmd = util.reltopdir('Tools/autotest/pysim/sim_wrapper.py') + ' --frame=%s --rate=400 --speedup=10 --home=%f,%f,%u,%u' % (
|
|
||||||
frame, HOME.lat, HOME.lng, HOME.alt, HOME.heading)
|
|
||||||
|
|
||||||
runsim = pexpect.spawn(sim_cmd, logfile=sys.stdout, timeout=10)
|
home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading)
|
||||||
runsim.delaybeforesend = 0
|
sil = util.start_SIL(atype, wipe=True, model=frame, home=home, speedup=10)
|
||||||
runsim.expect('Starting at lat')
|
|
||||||
|
|
||||||
sil = util.start_SIL(atype, wipe=True)
|
|
||||||
mavproxy = util.start_MAVProxy_SIL(atype)
|
mavproxy = util.start_MAVProxy_SIL(atype)
|
||||||
print("Dumping defaults")
|
print("Dumping defaults")
|
||||||
idx = mavproxy.expect(['Please Run Setup', 'Saved [0-9]+ parameters to (\S+)'])
|
idx = mavproxy.expect(['Please Run Setup', 'Saved [0-9]+ parameters to (\S+)'])
|
||||||
|
@ -38,7 +33,7 @@ def get_default_params(atype):
|
||||||
# we need to restart it after eeprom erase
|
# we need to restart it after eeprom erase
|
||||||
util.pexpect_close(mavproxy)
|
util.pexpect_close(mavproxy)
|
||||||
util.pexpect_close(sil)
|
util.pexpect_close(sil)
|
||||||
sil = util.start_SIL(atype)
|
sil = util.start_SIL(atype, model=frame, home=home, speedup=10)
|
||||||
mavproxy = util.start_MAVProxy_SIL(atype)
|
mavproxy = util.start_MAVProxy_SIL(atype)
|
||||||
idx = mavproxy.expect('Saved [0-9]+ parameters to (\S+)')
|
idx = mavproxy.expect('Saved [0-9]+ parameters to (\S+)')
|
||||||
parmfile = mavproxy.match.group(1)
|
parmfile = mavproxy.match.group(1)
|
||||||
|
@ -46,7 +41,6 @@ def get_default_params(atype):
|
||||||
shutil.copy(parmfile, dest)
|
shutil.copy(parmfile, dest)
|
||||||
util.pexpect_close(mavproxy)
|
util.pexpect_close(mavproxy)
|
||||||
util.pexpect_close(sil)
|
util.pexpect_close(sil)
|
||||||
util.pexpect_close(runsim)
|
|
||||||
print("Saved defaults for %s to %s" % (atype, dest))
|
print("Saved defaults for %s to %s" % (atype, dest))
|
||||||
return True
|
return True
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue