mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
Tools: use relative paths for parameter files
This commit is contained in:
parent
392911fc62
commit
6e91ae554a
@ -1658,7 +1658,7 @@ class AutoTest(ABC):
|
|||||||
if self.params is None:
|
if self.params is None:
|
||||||
self.params = self.model_defaults_filepath(self.frame)
|
self.params = self.model_defaults_filepath(self.frame)
|
||||||
for x in self.params:
|
for x in self.params:
|
||||||
self.repeatedly_apply_parameter_file(os.path.join(testdir, x))
|
self.repeatedly_apply_parameter_file(x)
|
||||||
|
|
||||||
def count_lines_in_filepath(self, filepath):
|
def count_lines_in_filepath(self, filepath):
|
||||||
return len([i for i in open(filepath)])
|
return len([i for i in open(filepath)])
|
||||||
@ -11695,7 +11695,7 @@ switch value'''
|
|||||||
defaults_filepath = [defaults_filepath]
|
defaults_filepath = [defaults_filepath]
|
||||||
defaults_list = []
|
defaults_list = []
|
||||||
for d in defaults_filepath:
|
for d in defaults_filepath:
|
||||||
defaults_list.append(os.path.join(testdir, d))
|
defaults_list.append(util.reltopdir(os.path.join(testdir, d)))
|
||||||
return defaults_list
|
return defaults_list
|
||||||
|
|
||||||
def load_default_params_file(self, filename):
|
def load_default_params_file(self, filename):
|
||||||
|
@ -408,10 +408,11 @@ def start_SITL(binary,
|
|||||||
cmd.extend(['--speedup', str(speedup)])
|
cmd.extend(['--speedup', str(speedup)])
|
||||||
if defaults_filepath is not None:
|
if defaults_filepath is not None:
|
||||||
if type(defaults_filepath) == list:
|
if type(defaults_filepath) == list:
|
||||||
if len(defaults_filepath):
|
defaults = [reltopdir(path) for path in defaults_filepath]
|
||||||
cmd.extend(['--defaults', ",".join(defaults_filepath)])
|
if len(defaults):
|
||||||
|
cmd.extend(['--defaults', ",".join(defaults)])
|
||||||
else:
|
else:
|
||||||
cmd.extend(['--defaults', defaults_filepath])
|
cmd.extend(['--defaults', reltopdir(defaults_filepath)])
|
||||||
if unhide_parameters:
|
if unhide_parameters:
|
||||||
cmd.extend(['--unhide-groups'])
|
cmd.extend(['--unhide-groups'])
|
||||||
# somewhere for MAVProxy to connect to:
|
# somewhere for MAVProxy to connect to:
|
||||||
|
@ -28,6 +28,7 @@ import shlex
|
|||||||
import binascii
|
import binascii
|
||||||
import math
|
import math
|
||||||
|
|
||||||
|
from pysim import util
|
||||||
from pysim import vehicleinfo
|
from pysim import vehicleinfo
|
||||||
|
|
||||||
|
|
||||||
@ -683,7 +684,7 @@ def start_vehicle(binary, opts, stuff, spawns=None):
|
|||||||
paths = stuff["default_params_filename"]
|
paths = stuff["default_params_filename"]
|
||||||
if not isinstance(paths, list):
|
if not isinstance(paths, list):
|
||||||
paths = [paths]
|
paths = [paths]
|
||||||
paths = [os.path.join(autotest_dir, x) for x in paths]
|
paths = [util.reltopdir(os.path.join(autotest_dir, x)) for x in paths]
|
||||||
for x in paths:
|
for x in paths:
|
||||||
if not os.path.isfile(x):
|
if not os.path.isfile(x):
|
||||||
print("The parameter file (%s) does not exist" % (x,))
|
print("The parameter file (%s) does not exist" % (x,))
|
||||||
|
Loading…
Reference in New Issue
Block a user