From 5eab069a384645114ed0fb0ae60f7887914d9f63 Mon Sep 17 00:00:00 2001 From: Fabian Oboril Date: Wed, 25 Aug 2021 13:02:08 +0200 Subject: [PATCH] Fixed exception when using evaluation criteria with OSC Using a delay value of '0.0' or '.0' caused an exception Minor: - Fixed pylint recommendations Change-Id: Idb9cc2c01bd81f87c5ae8fc18bee8919040d8f24 --- Docs/CHANGELOG.md | 1 + scenario_runner.py | 6 +++--- .../scenarioconfigs/openscenario_configuration.py | 6 +++--- srunner/scenariomanager/carla_data_provider.py | 12 ++++++------ srunner/scenariomanager/result_writer.py | 6 +++--- srunner/tools/openscenario_parser.py | 8 ++++---- srunner/tools/route_parser.py | 2 +- srunner/tools/scenario_helper.py | 2 +- 8 files changed, 22 insertions(+), 21 deletions(-) diff --git a/Docs/CHANGELOG.md b/Docs/CHANGELOG.md index dcbd8d379..f304c8ddc 100644 --- a/Docs/CHANGELOG.md +++ b/Docs/CHANGELOG.md @@ -29,6 +29,7 @@ * Fixed bug at the Getting Started docs which caused an import error * Fixed neverending lane change maneuver in OpenSCENARIO * Fixed bug causing the spawning of an actor with `request_new_actor` to never activate the autopilot. +* Fixed handling of evaluation criteria in OpenSCENARIO (using a delay value of .0 caused an exception) ### :ghost: Maintenance * Extended SimpleVehicleController (OSC) to handle traffic lights * Generalized visualizer attached to OSC controllers diff --git a/scenario_runner.py b/scenario_runner.py index 193e4644d..f88545b87 100755 --- a/scenario_runner.py +++ b/scenario_runner.py @@ -276,7 +276,7 @@ def _record_criteria(self, criteria, name): file_name = name[:-4] + ".json" # Filter the attributes that aren't JSON serializable - with open('temp.json', 'w') as fp: + with open('temp.json', 'w', encoding='utf-8') as fp: criteria_dict = {} for criterion in criteria: @@ -296,7 +296,7 @@ def _record_criteria(self, criteria, name): os.remove('temp.json') # Save the criteria dictionary into a .json file - with open(file_name, 'w') as fp: + with open(file_name, 'w', encoding='utf-8') as fp: json.dump(criteria_dict, fp, sort_keys=False, indent=4) def _load_and_wait_for_world(self, town, ego_vehicles=None): @@ -484,7 +484,7 @@ def _run_openscenario(self): self._cleanup() return False - openscenario_params = dict() + openscenario_params = {} if self._args.openscenarioparams is not None: for entry in self._args.openscenarioparams.split(','): [key, val] = [m.strip() for m in entry.split(':')] diff --git a/srunner/scenarioconfigs/openscenario_configuration.py b/srunner/scenarioconfigs/openscenario_configuration.py index f7a3df4d6..b0a209bd8 100644 --- a/srunner/scenarioconfigs/openscenario_configuration.py +++ b/srunner/scenarioconfigs/openscenario_configuration.py @@ -35,7 +35,7 @@ def __init__(self, filename, client, custom_params): self.xml_tree = ET.parse(filename) self.filename = filename - self._custom_params = custom_params if custom_params is not None else dict() + self._custom_params = custom_params if custom_params is not None else {} self._validate_openscenario_configuration() self.client = client @@ -175,7 +175,7 @@ def _set_carla_town(self): if world is None or (wmap is not None and wmap.name != self.town): if ".xodr" in self.town: - with open(self.town) as od_file: + with open(self.town, 'r', encoding='utf-8') as od_file: data = od_file.read() index = data.find('') data = data[index:] @@ -236,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') - args = dict() + args = {} for prop in obj.iter("Property"): key = prop.get('name') value = prop.get('value') diff --git a/srunner/scenariomanager/carla_data_provider.py b/srunner/scenariomanager/carla_data_provider.py index 11ac1088f..e8fdc71a9 100644 --- a/srunner/scenariomanager/carla_data_provider.py +++ b/srunner/scenariomanager/carla_data_provider.py @@ -46,11 +46,11 @@ class CarlaDataProvider(object): # pylint: disable=too-many-public-methods In addition it provides access to the map and the transform of all traffic lights """ - _actor_velocity_map = dict() - _actor_location_map = dict() - _actor_transform_map = dict() - _traffic_light_map = dict() - _carla_actor_pool = dict() + _actor_velocity_map = {} + _actor_location_map = {} + _actor_transform_map = {} + _traffic_light_map = {} + _carla_actor_pool = {} _client = None _world = None _map = None @@ -797,7 +797,7 @@ def cleanup(): CarlaDataProvider._world = None CarlaDataProvider._sync_flag = False CarlaDataProvider._ego_vehicle_route = None - CarlaDataProvider._carla_actor_pool = dict() + CarlaDataProvider._carla_actor_pool = {} CarlaDataProvider._client = None CarlaDataProvider._spawn_points = None CarlaDataProvider._spawn_index = 0 diff --git a/srunner/scenariomanager/result_writer.py b/srunner/scenariomanager/result_writer.py index 02129b5c8..b7e0dce20 100644 --- a/srunner/scenariomanager/result_writer.py +++ b/srunner/scenariomanager/result_writer.py @@ -57,7 +57,7 @@ def write(self): output = self.create_output_text() if self._filename is not None: - with open(self._filename, 'w') as fd: + with open(self._filename, 'w', encoding='utf-8') as fd: fd.write(output) if self._stdout: print(output) @@ -203,7 +203,7 @@ def result_dict(name, actor, optional, expected, actual, success): "criteria": json_list } - with open(self._json, "w") as fp: + with open(self._json, "w", encoding='utf-8') as fp: json.dump(result_object, fp, indent=4) def _write_to_junit(self): @@ -222,7 +222,7 @@ def _write_to_junit(self): if self._data.scenario_duration_game >= self._data.scenario.timeout: failure_count += 1 - with open(self._junit, "w") as junit_file: + with open(self._junit, "w", encoding='utf-8') as junit_file: junit_file.write("\n") diff --git a/srunner/tools/openscenario_parser.py b/srunner/tools/openscenario_parser.py index df6561cac..2b73ddf53 100644 --- a/srunner/tools/openscenario_parser.py +++ b/srunner/tools/openscenario_parser.py @@ -111,7 +111,7 @@ class OpenScenarioParser(object): "OFF": carla.TrafficLightState.Off, } - global_osc_parameters = dict() + global_osc_parameters = {} use_carla_coordinate_system = False osc_filepath = None @@ -182,7 +182,7 @@ def set_parameters(xml_tree, additional_parameter_dict=None): updated xml_tree, dictonary containing all parameters and their values """ - parameter_dict = dict() + parameter_dict = {} parameters = xml_tree.find('ParameterDeclarations') if parameters is None and not parameter_dict: @@ -254,7 +254,7 @@ def assign_catalog_parameters(entry_instance, catalog_reference): updated entry_instance with updated parameter values """ - parameter_dict = dict() + parameter_dict = {} for elem in entry_instance.iter(): if elem.find('ParameterDeclarations') is not None: parameters = elem.find('ParameterDeclarations') @@ -690,7 +690,7 @@ def convert_condition_to_atomic(condition, actor_list): delay_atomic = None condition_name = condition.attrib.get('name') - if condition.attrib.get('delay') is not None and str(condition.attrib.get('delay')) != '0': + if condition.attrib.get('delay') is not None and float(condition.attrib.get('delay')) != 0: delay = float(condition.attrib.get('delay')) delay_atomic = TimeOut(delay) diff --git a/srunner/tools/route_parser.py b/srunner/tools/route_parser.py index bff929c49..18899a54f 100644 --- a/srunner/tools/route_parser.py +++ b/srunner/tools/route_parser.py @@ -34,7 +34,7 @@ def parse_annotations_file(annotation_filename): :return: """ - with open(annotation_filename, 'r') as f: + with open(annotation_filename, 'r', encoding='utf-8') as f: annotation_dict = json.loads(f.read()) final_dict = {} diff --git a/srunner/tools/scenario_helper.py b/srunner/tools/scenario_helper.py index 8de898321..b9b54b6bf 100644 --- a/srunner/tools/scenario_helper.py +++ b/srunner/tools/scenario_helper.py @@ -414,7 +414,7 @@ def choose_at_junction(current_waypoint, next_choices, direction=0): y=math.sin(math.radians(current_transform.rotation.yaw))) current_vector = vector(current_location, projected_location) cross_list = [] - cross_to_waypoint = dict() + cross_to_waypoint = {} for waypoint in next_choices: waypoint = waypoint.next(10)[0] select_vector = vector(current_location, waypoint.transform.location)