mirror of https://github.com/ArduPilot/ardupilot
autotest: plane: fix flyeachframe param loading
This was previously fixed in copter
This commit is contained in:
parent
5c9003dd02
commit
058f66fbe6
|
@ -9462,9 +9462,6 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
self.progress("Actually, no I'm not - it is an external simulation")
|
||||
continue
|
||||
model = frame_bits.get("model", frame)
|
||||
# the model string for Callisto has crap in it.... we
|
||||
# should really have another entry in the vehicleinfo data
|
||||
# to carry the path to the JSON.
|
||||
defaults = self.model_defaults_filepath(frame)
|
||||
if not isinstance(defaults, list):
|
||||
defaults = [defaults]
|
||||
|
|
|
@ -4219,11 +4219,7 @@ class AutoTestPlane(vehicle_test_suite.TestSuite):
|
|||
self.progress("Actually, no I'm not - it is an external simulation")
|
||||
continue
|
||||
model = frame_bits.get("model", frame)
|
||||
# the model string for Callisto has crap in it.... we
|
||||
# should really have another entry in the vehicleinfo data
|
||||
# to carry the path to the JSON.
|
||||
actual_model = model.split(":")[0]
|
||||
defaults = self.model_defaults_filepath(actual_model)
|
||||
defaults = self.model_defaults_filepath(frame)
|
||||
if not isinstance(defaults, list):
|
||||
defaults = [defaults]
|
||||
self.customise_SITL_commandline(
|
||||
|
|
Loading…
Reference in New Issue