Tools: add a --speedup parameter to autotest to control speed of all sims
This commit is contained in:
parent
30fac9160e
commit
1b7122d733
@ -100,7 +100,7 @@ def drive_mission(mavproxy, mav, filename):
|
||||
|
||||
vinfo = vehicleinfo.VehicleInfo()
|
||||
|
||||
def drive_APMrover2(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params=None, gdbserver=False):
|
||||
def drive_APMrover2(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params=None, gdbserver=False, speedup=10):
|
||||
"""Drive APMrover2 in SITL.
|
||||
|
||||
you can pass viewerip as an IP address to optionally send fg and
|
||||
@ -118,7 +118,7 @@ def drive_APMrover2(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fa
|
||||
options += ' --map'
|
||||
|
||||
home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading)
|
||||
sitl = util.start_SITL(binary, wipe=True, model=frame, home=home, speedup=10)
|
||||
sitl = util.start_SITL(binary, wipe=True, model=frame, home=home, speedup=speedup)
|
||||
mavproxy = util.start_MAVProxy_SITL('APMrover2', options=options)
|
||||
|
||||
print("WAITING FOR PARAMETERS")
|
||||
@ -140,7 +140,7 @@ def drive_APMrover2(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fa
|
||||
util.pexpect_close(mavproxy)
|
||||
util.pexpect_close(sitl)
|
||||
|
||||
sitl = util.start_SITL(binary, model='rover', home=home, speedup=10, valgrind=valgrind, gdb=gdb, gdbserver=gdbserver)
|
||||
sitl = util.start_SITL(binary, model='rover', home=home, speedup=speedup, valgrind=valgrind, gdb=gdb, gdbserver=gdbserver)
|
||||
mavproxy = util.start_MAVProxy_SITL('APMrover2', options=options)
|
||||
mavproxy.expect('Telemetry log: (\S+)')
|
||||
logfile = mavproxy.match.group(1)
|
||||
|
@ -29,7 +29,6 @@ AVCHOME = mavutil.location(40.072842, -105.230575, 1586, 0)
|
||||
|
||||
homeloc = None
|
||||
num_wp = 0
|
||||
speedup_default = 10
|
||||
|
||||
|
||||
def wait_ready_to_arm(mavproxy):
|
||||
@ -972,7 +971,7 @@ def setup_rc(mavproxy):
|
||||
mavproxy.send('rc 3 1000\n')
|
||||
|
||||
|
||||
def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params=None, gdbserver=False):
|
||||
def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params=None, gdbserver=False, speedup=10):
|
||||
"""Fly ArduCopter in SITL.
|
||||
|
||||
you can pass viewerip as an IP address to optionally send fg and
|
||||
@ -984,7 +983,7 @@ def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fal
|
||||
frame = '+'
|
||||
|
||||
home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading)
|
||||
sitl = util.start_SITL(binary, wipe=True, model=frame, home=home, speedup=speedup_default)
|
||||
sitl = util.start_SITL(binary, wipe=True, model=frame, home=home, speedup=speedup)
|
||||
mavproxy = util.start_MAVProxy_SITL('ArduCopter', options='--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter')
|
||||
mavproxy.expect('Received [0-9]+ parameters')
|
||||
|
||||
@ -1004,7 +1003,7 @@ def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fal
|
||||
util.pexpect_close(mavproxy)
|
||||
util.pexpect_close(sitl)
|
||||
|
||||
sitl = util.start_SITL(binary, model=frame, home=home, speedup=speedup_default, valgrind=valgrind, gdb=gdb, gdbserver=gdbserver)
|
||||
sitl = util.start_SITL(binary, model=frame, home=home, speedup=speedup, valgrind=valgrind, gdb=gdb, gdbserver=gdbserver)
|
||||
options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --quadcopter --streamrate=5'
|
||||
if viewerip:
|
||||
options += ' --out=%s:14550' % viewerip
|
||||
@ -1329,7 +1328,7 @@ def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fal
|
||||
return True
|
||||
|
||||
|
||||
def fly_CopterAVC(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params=None, gdbserver=False):
|
||||
def fly_CopterAVC(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params=None, gdbserver=False, speedup=10):
|
||||
"""Fly ArduCopter in SITL for AVC2013 mission."""
|
||||
global homeloc
|
||||
|
||||
@ -1337,7 +1336,7 @@ def fly_CopterAVC(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fals
|
||||
frame = 'heli'
|
||||
|
||||
home = "%f,%f,%u,%u" % (AVCHOME.lat, AVCHOME.lng, AVCHOME.alt, AVCHOME.heading)
|
||||
sitl = util.start_SITL(binary, wipe=True, model=frame, home=home, speedup=speedup_default)
|
||||
sitl = util.start_SITL(binary, wipe=True, model=frame, home=home, speedup=speedup)
|
||||
mavproxy = util.start_MAVProxy_SITL('ArduCopter', options='--sitl=127.0.0.1:5501 --out=127.0.0.1:19550')
|
||||
mavproxy.expect('Received [0-9]+ parameters')
|
||||
|
||||
@ -1357,7 +1356,7 @@ def fly_CopterAVC(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fals
|
||||
util.pexpect_close(mavproxy)
|
||||
util.pexpect_close(sitl)
|
||||
|
||||
sitl = util.start_SITL(binary, model='heli', home=home, speedup=speedup_default, valgrind=valgrind, gdb=gdb, gdbserver=gdbserver)
|
||||
sitl = util.start_SITL(binary, model='heli', home=home, speedup=speedup, valgrind=valgrind, gdb=gdb, gdbserver=gdbserver)
|
||||
options = '--sitl=127.0.0.1:5501 --out=127.0.0.1:19550 --streamrate=5'
|
||||
if viewerip:
|
||||
options += ' --out=%s:14550' % viewerip
|
||||
|
@ -440,7 +440,7 @@ def fly_mission(mavproxy, mav, filename, height_accuracy=-1, target_altitude=Non
|
||||
return True
|
||||
|
||||
|
||||
def fly_ArduPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, gdbserver=False):
|
||||
def fly_ArduPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, gdbserver=False, speedup=10):
|
||||
"""Fly ArduPlane in SITL.
|
||||
|
||||
you can pass viewerip as an IP address to optionally send fg and
|
||||
@ -454,7 +454,7 @@ def fly_ArduPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fals
|
||||
if use_map:
|
||||
options += ' --map'
|
||||
|
||||
sitl = util.start_SITL(binary, model='plane-elevrev', home=HOME_LOCATION, speedup=10,
|
||||
sitl = util.start_SITL(binary, model='plane-elevrev', home=HOME_LOCATION, speedup=speedup,
|
||||
valgrind=valgrind, gdb=gdb, gdbserver=gdbserver,
|
||||
defaults_file=os.path.join(testdir, 'default_params/plane-jsbsim.parm'))
|
||||
mavproxy = util.start_MAVProxy_SITL('ArduPlane', options=options)
|
||||
|
@ -92,7 +92,7 @@ def dive_mission(mavproxy, mav, filename):
|
||||
print("Mission OK")
|
||||
return True
|
||||
|
||||
def dive_ArduSub(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, gdbserver=False):
|
||||
def dive_ArduSub(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, gdbserver=False, speedup=10):
|
||||
"""Dive ArduSub in SITL.
|
||||
|
||||
you can pass viewerip as an IP address to optionally send fg and
|
||||
@ -105,7 +105,7 @@ def dive_ArduSub(binary, viewerip=None, use_map=False, valgrind=False, gdb=False
|
||||
options += ' --map'
|
||||
|
||||
home = "%f,%f,%u,%u" % (HOME.lat, HOME.lng, HOME.alt, HOME.heading)
|
||||
sitl = util.start_SITL(binary, model='vectored', wipe=True, home=home, speedup=10)
|
||||
sitl = util.start_SITL(binary, model='vectored', wipe=True, home=home, speedup=speedup)
|
||||
mavproxy = util.start_MAVProxy_SITL('ArduSub', options=options)
|
||||
mavproxy.expect('Received [0-9]+ parameters')
|
||||
|
||||
@ -121,7 +121,7 @@ def dive_ArduSub(binary, viewerip=None, use_map=False, valgrind=False, gdb=False
|
||||
util.pexpect_close(mavproxy)
|
||||
util.pexpect_close(sitl)
|
||||
|
||||
sitl = util.start_SITL(binary, model='vectored', home=home, speedup=10, valgrind=valgrind, gdb=gdb, gdbserver=gdbserver)
|
||||
sitl = util.start_SITL(binary, model='vectored', home=home, speedup=speedup, valgrind=valgrind, gdb=gdb, gdbserver=gdbserver)
|
||||
mavproxy = util.start_MAVProxy_SITL('ArduSub', options=options)
|
||||
mavproxy.expect('Telemetry log: (\S+)')
|
||||
logfile = mavproxy.match.group(1)
|
||||
|
@ -222,23 +222,33 @@ def run_step(step):
|
||||
vehicle = step[8:]
|
||||
return get_default_params(vehicle, binary)
|
||||
|
||||
fly_opts = {
|
||||
"viewerip": opts.viewerip,
|
||||
"use_map": opts.map,
|
||||
"valgrind": opts.valgrind,
|
||||
"gdb": opts.gdb,
|
||||
"gdbserver": opts.gdbserver,
|
||||
}
|
||||
if opts.speedup is not None:
|
||||
fly_opts.speedup = opts.speedup
|
||||
|
||||
if step == 'fly.ArduCopter':
|
||||
return arducopter.fly_ArduCopter(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb, frame=opts.frame, gdbserver=opts.gdbserver)
|
||||
return arducopter.fly_ArduCopter(binary, frame=opts.frame, **fly_opts)
|
||||
|
||||
if step == 'fly.CopterAVC':
|
||||
return arducopter.fly_CopterAVC(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb, frame=opts.frame, gdbserver=opts.gdbserver)
|
||||
return arducopter.fly_CopterAVC(binary, **fly_opts)
|
||||
|
||||
if step == 'fly.ArduPlane':
|
||||
return arduplane.fly_ArduPlane(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb, gdbserver=opts.gdbserver)
|
||||
return arduplane.fly_ArduPlane(binary, **fly_opts)
|
||||
|
||||
if step == 'fly.QuadPlane':
|
||||
return quadplane.fly_QuadPlane(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb, gdbserver=opts.gdbserver)
|
||||
return quadplane.fly_QuadPlane(binary, **fly_opts)
|
||||
|
||||
if step == 'drive.APMrover2':
|
||||
return apmrover2.drive_APMrover2(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb, frame=opts.frame, gdbserver=opts.gdbserver)
|
||||
return apmrover2.drive_APMrover2(binary, frame=opts.frame, **fly_opts)
|
||||
|
||||
if step == 'dive.ArduSub':
|
||||
return ardusub.dive_ArduSub(binary, viewerip=opts.viewerip, use_map=opts.map, valgrind=opts.valgrind, gdb=opts.gdb, gdbserver=opts.gdbserver)
|
||||
return ardusub.dive_ArduSub(binary, **fly_opts)
|
||||
|
||||
if step == 'build.All':
|
||||
return build_all()
|
||||
@ -435,6 +445,7 @@ if __name__ == "__main__":
|
||||
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("--timeout", default=3000, type='int', help='maximum runtime in seconds')
|
||||
parser.add_option("--speedup", default=None, type='int', help='speedup to run the simulations at')
|
||||
parser.add_option("--valgrind", default=False, action='store_true', help='run ArduPilot binaries under valgrind')
|
||||
parser.add_option("--gdb", default=False, action='store_true', help='run ArduPilot binaries under gdb')
|
||||
parser.add_option("--debug", default=False, action='store_true', help='make built binaries debug binaries')
|
||||
|
@ -44,7 +44,7 @@ def fly_mission(mavproxy, mav, filename, fence, height_accuracy=-1):
|
||||
return True
|
||||
|
||||
|
||||
def fly_QuadPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, gdbserver=False):
|
||||
def fly_QuadPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, gdbserver=False, speedup=10):
|
||||
"""Fly QuadPlane in SITL.
|
||||
|
||||
you can pass viewerip as an IP address to optionally send fg and
|
||||
@ -58,7 +58,7 @@ def fly_QuadPlane(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fals
|
||||
if use_map:
|
||||
options += ' --map'
|
||||
|
||||
sitl = util.start_SITL(binary, model='quadplane', wipe=True, home=HOME_LOCATION, speedup=10,
|
||||
sitl = util.start_SITL(binary, model='quadplane', wipe=True, home=HOME_LOCATION, speedup=speedup,
|
||||
defaults_file=os.path.join(testdir, 'default_params/quadplane.parm'), valgrind=valgrind, gdb=gdb, gdbserver=gdbserver)
|
||||
mavproxy = util.start_MAVProxy_SITL('QuadPlane', options=options)
|
||||
mavproxy.expect('Telemetry log: (\S+)')
|
||||
|
Loading…
Reference in New Issue
Block a user