mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-27 02:58:31 -04:00
Tools: use path relative to current directory to load parameters
This commit is contained in:
parent
b3e78e1e8d
commit
5cb1444b1d
@ -57,6 +57,9 @@ def topdir():
|
||||
d = os.path.dirname(d)
|
||||
return d
|
||||
|
||||
def relcurdir(path):
|
||||
"""Return a path relative to current dir"""
|
||||
return os.path.relpath(path, os.getcwd())
|
||||
|
||||
def reltopdir(path):
|
||||
"""Return a path relative to topdir()."""
|
||||
|
@ -684,7 +684,7 @@ def start_vehicle(binary, opts, stuff, spawns=None):
|
||||
paths = stuff["default_params_filename"]
|
||||
if not isinstance(paths, list):
|
||||
paths = [paths]
|
||||
paths = [util.reltopdir(os.path.join(autotest_dir, x)) for x in paths]
|
||||
paths = [util.relcurdir(os.path.join(autotest_dir, x)) for x in paths]
|
||||
for x in paths:
|
||||
if not os.path.isfile(x):
|
||||
print("The parameter file (%s) does not exist" % (x,))
|
||||
|
Loading…
Reference in New Issue
Block a user