Skip to content

Commit

Permalink
Further fixes to OSC Parameter handling
Browse files Browse the repository at this point in the history
Change-Id: Id03cfeb1813ec8aec7704d075ff6b9abefc01eb4
  • Loading branch information
fabianoboril committed Nov 9, 2021
1 parent 19c8d59 commit 4c0b72c
Show file tree
Hide file tree
Showing 2 changed files with 115 additions and 97 deletions.
27 changes: 14 additions & 13 deletions srunner/scenarioconfigs/openscenario_configuration.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!/usr/bin/env python

# Copyright (c) 2019 Intel Corporation
# Copyright (c) 2019-2021 Intel Corporation
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
Expand Down Expand Up @@ -124,7 +124,8 @@ def _load_catalogs(self):
if catalog is None:
continue

catalog_path = catalog.find("Directory").attrib.get('path') + "/" + catalog_type + "Catalog.xosc"
catalog_path = str(ParameterRef(catalog.find("Directory").attrib.get('path'))) + \
"/" + catalog_type + "Catalog.xosc"
if not os.path.isabs(catalog_path) and "xosc" in self.filename:
catalog_path = os.path.dirname(os.path.abspath(self.filename)) + "/" + catalog_path

Expand All @@ -134,10 +135,10 @@ def _load_catalogs(self):
xml_tree = ET.parse(catalog_path)
self._validate_openscenario_catalog_configuration(xml_tree)
catalog = xml_tree.find("Catalog")
catalog_name = catalog.attrib.get("name")
catalog_name = str(ParameterRef(catalog.attrib.get("name")))
self.catalogs[catalog_name] = {}
for entry in catalog:
self.catalogs[catalog_name][entry.attrib.get("name")] = entry
self.catalogs[catalog_name][str(ParameterRef(entry.attrib.get("name")))] = entry

def _set_scenario_name(self):
"""
Expand All @@ -158,7 +159,7 @@ def _set_carla_town(self):
Hence, there can be multiple towns specified. We just use the _last_ one.
"""
for logic in self.xml_tree.find("RoadNetwork").findall("LogicFile"):
self.town = logic.attrib.get('filepath', None)
self.town = str(ParameterRef(logic.attrib.get('filepath', None)))

if self.town is not None and ".xodr" in self.town:
if not os.path.isabs(self.town):
Expand Down Expand Up @@ -235,7 +236,7 @@ def _set_actor_information(self):
"""
for entity in self.xml_tree.iter("Entities"):
for obj in entity.iter("ScenarioObject"):
rolename = obj.attrib.get('name', 'simulation')
rolename = str(ParameterRef(obj.attrib.get('name', 'simulation')))
args = {}
for prop in obj.iter("Property"):
key = prop.get('name')
Expand Down Expand Up @@ -290,8 +291,8 @@ def _extract_vehicle_information(self, obj, rolename, vehicle, args):
Helper function to _set_actor_information for getting vehicle information from XML tree
"""
color = None
model = vehicle.attrib.get('name', "vehicle.*")
category = vehicle.attrib.get('vehicleCategory', "car")
model = str(ParameterRef(vehicle.attrib.get('name', "vehicle.*")))
category = str(ParameterRef(vehicle.attrib.get('vehicleCategory', "car")))
ego_vehicle = False
for prop in obj.iter("Property"):
if prop.get('name', '') == 'type':
Expand All @@ -312,7 +313,7 @@ def _extract_pedestrian_information(self, obj, rolename, pedestrian, args):
"""
Helper function to _set_actor_information for getting pedestrian information from XML tree
"""
model = pedestrian.attrib.get('model', "walker.*")
model = str(ParameterRef(pedestrian.attrib.get('model', "walker.*")))

speed = self._get_actor_speed(rolename)
new_actor = ActorConfigurationData(model, None, rolename, speed, category="pedestrian", args=args)
Expand All @@ -323,13 +324,13 @@ def _extract_misc_information(self, obj, rolename, misc, args):
"""
Helper function to _set_actor_information for getting vehicle information from XML tree
"""
category = misc.attrib.get('miscObjectCategory')
category = str(ParameterRef(misc.attrib.get('miscObjectCategory')))
if category == "barrier":
model = "static.prop.streetbarrier"
elif category == "guardRail":
model = "static.prop.chainbarrier"
else:
model = misc.attrib.get('name')
model = str(ParameterRef(misc.attrib.get('name')))
new_actor = ActorConfigurationData(model, None, rolename, category="misc", args=args)

self.other_actors.append(new_actor)
Expand All @@ -351,7 +352,7 @@ def _get_actor_transform(self, actor_name):
actor_found = False

for private_action in self.init.iter("Private"):
if private_action.attrib.get('entityRef', None) == actor_name:
if str(ParameterRef(private_action.attrib.get('entityRef', None))) == actor_name:
if actor_found:
# pylint: disable=line-too-long
self.logger.warning(
Expand Down Expand Up @@ -380,7 +381,7 @@ def _get_actor_speed(self, actor_name):
actor_found = False

for private_action in self.init.iter("Private"):
if private_action.attrib.get('entityRef', None) == actor_name:
if str(ParameterRef(private_action.attrib.get('entityRef', None))) == actor_name:
if actor_found:
# pylint: disable=line-too-long
self.logger.warning(
Expand Down
Loading

0 comments on commit 4c0b72c

Please sign in to comment.