mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
autotest: stop passing defaults in via --defaults to custom_sitl_commandline
This commit is contained in:
parent
ca4fd52b95
commit
5ba8755802
@ -7652,7 +7652,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
ex = None
|
||||
try:
|
||||
self.customise_SITL_commandline(
|
||||
["--defaults", ','.join(self.model_defaults_filepath('Callisto'))],
|
||||
[],
|
||||
defaults_filepath=self.model_defaults_filepath('Callisto'),
|
||||
model="octa-quad:@ROMFS/models/Callisto.json",
|
||||
wipe=True,
|
||||
)
|
||||
@ -8847,7 +8848,8 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
||||
def Callisto(self):
|
||||
'''Test Callisto'''
|
||||
self.customise_SITL_commandline(
|
||||
["--defaults", ','.join(self.model_defaults_filepath('Callisto')), ],
|
||||
[],
|
||||
defaults_filepath=self.model_defaults_filepath('Callisto'),
|
||||
model="octa-quad:@ROMFS/models/Callisto.json",
|
||||
wipe=True,
|
||||
)
|
||||
|
@ -3917,7 +3917,8 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
||||
if not isinstance(defaults, list):
|
||||
defaults = [defaults]
|
||||
self.customise_SITL_commandline(
|
||||
["--defaults", ','.join(defaults), ],
|
||||
[],
|
||||
defaults_filepath=defaults,
|
||||
model=model,
|
||||
wipe=True,
|
||||
)
|
||||
|
@ -199,7 +199,8 @@ class AutoTestHelicopter(AutoTestCopter):
|
||||
if not isinstance(defaults, list):
|
||||
defaults = [defaults]
|
||||
self.customise_SITL_commandline(
|
||||
["--defaults", ','.join(defaults), ],
|
||||
[],
|
||||
defaults_filepath=defaults,
|
||||
model=model,
|
||||
wipe=True,
|
||||
)
|
||||
@ -210,7 +211,8 @@ class AutoTestHelicopter(AutoTestCopter):
|
||||
def governortest(self):
|
||||
'''Test Heli Internal Throttle Curve and Governor'''
|
||||
self.customise_SITL_commandline(
|
||||
["--defaults", ','.join(self.model_defaults_filepath('heli-gas')), ],
|
||||
[],
|
||||
defaults_filepath=self.model_defaults_filepath('heli-gas'),
|
||||
model="heli-gas",
|
||||
wipe=True,
|
||||
)
|
||||
|
@ -542,6 +542,9 @@ def start_SITL(binary,
|
||||
|
||||
cmd.extend(customisations)
|
||||
|
||||
if "--defaults" in customisations:
|
||||
raise ValueError("--defaults must be passed in via defaults_filepath keyword argument, not as part of customisation list") # noqa
|
||||
|
||||
pexpect_logfile_prefix = stdout_prefix
|
||||
if pexpect_logfile_prefix is None:
|
||||
pexpect_logfile_prefix = os.path.basename(binary)
|
||||
|
Loading…
Reference in New Issue
Block a user