Skip to content

Commit

Permalink
Fixed exception when using evaluation criteria with OSC
Browse files Browse the repository at this point in the history
Using a delay value of '0.0' or '.0' caused an exception

Minor:
- Fixed pylint recommendations

Change-Id: Idb9cc2c01bd81f87c5ae8fc18bee8919040d8f24
  • Loading branch information
fabianoboril authored Aug 25, 2021
1 parent 679a83c commit 5eab069
Show file tree
Hide file tree
Showing 8 changed files with 22 additions and 21 deletions.
1 change: 1 addition & 0 deletions Docs/CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
6 changes: 3 additions & 3 deletions scenario_runner.py
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand All @@ -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):
Expand Down Expand Up @@ -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(':')]
Expand Down
6 changes: 3 additions & 3 deletions srunner/scenarioconfigs/openscenario_configuration.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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('<OpenDRIVE>')
data = data[index:]
Expand Down Expand Up @@ -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')
Expand Down
12 changes: 6 additions & 6 deletions srunner/scenariomanager/carla_data_provider.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down
6 changes: 3 additions & 3 deletions srunner/scenariomanager/result_writer.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down Expand Up @@ -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):
Expand All @@ -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("<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n")

Expand Down
8 changes: 4 additions & 4 deletions srunner/tools/openscenario_parser.py
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down Expand Up @@ -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:
Expand Down Expand Up @@ -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')
Expand Down Expand Up @@ -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)

Expand Down
2 changes: 1 addition & 1 deletion srunner/tools/route_parser.py
Original file line number Diff line number Diff line change
Expand Up @@ -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 = {}
Expand Down
2 changes: 1 addition & 1 deletion srunner/tools/scenario_helper.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down

0 comments on commit 5eab069

Please sign in to comment.