mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
autotest: start_SITL understands SIM_RATE_HZ
This commit is contained in:
parent
47a1b460bc
commit
f4c5c56b7d
@ -438,6 +438,7 @@ def start_SITL(binary,
|
||||
home=None,
|
||||
model=None,
|
||||
speedup=1,
|
||||
sim_rate_hz=None,
|
||||
defaults_filepath=None,
|
||||
unhide_parameters=False,
|
||||
gdbserver=False,
|
||||
@ -531,8 +532,10 @@ def start_SITL(binary,
|
||||
if home is not None:
|
||||
cmd.extend(['--home', home])
|
||||
cmd.extend(['--model', model])
|
||||
if speedup != 1:
|
||||
if speedup is not None and speedup != 1:
|
||||
cmd.extend(['--speedup', str(speedup)])
|
||||
if sim_rate_hz is not None:
|
||||
cmd.extend(['--rate', str(sim_rate_hz)])
|
||||
if defaults_filepath is not None:
|
||||
if type(defaults_filepath) == list:
|
||||
defaults = [reltopdir(path) for path in defaults_filepath]
|
||||
|
Loading…
Reference in New Issue
Block a user