Tools: autotest: correct Copter params file handling

This commit is contained in:
Peter Barker 2017-05-27 13:42:56 +10:00 committed by Francisco Ferreira
parent 6615aee0b1
commit 59647b3434

View File

@ -960,7 +960,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_file=None):
def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=False, frame=None, params=None):
"""Fly ArduCopter in SITL.
you can pass viewerip as an IP address to optionally send fg and
@ -977,13 +977,13 @@ def fly_ArduCopter(binary, viewerip=None, use_map=False, valgrind=False, gdb=Fal
mavproxy.expect('Received [0-9]+ parameters')
# setup test parameters
if params_file is None:
if params is None:
params = vinfo.options["ArduCopter"]["frames"][frame]["default_params_filename"]
if not isinstance(params, list):
params = [params]
for x in params:
mavproxy.send("param load %s\n" % os.path.join(testdir, x))
mavproxy.expect('Loaded [0-9]+ parameters')
if not isinstance(params, list):
params = [params]
for x in params:
mavproxy.send("param load %s\n" % os.path.join(testdir, x))
mavproxy.expect('Loaded [0-9]+ parameters')
mavproxy.send("param set LOG_REPLAY 1\n")
mavproxy.send("param set LOG_DISARMED 1\n")
time.sleep(3)