diff --git a/.github/workflows/static_code_check.yml b/.github/workflows/static_code_check.yml index 0cf08f377..db310ebb0 100644 --- a/.github/workflows/static_code_check.yml +++ b/.github/workflows/static_code_check.yml @@ -20,15 +20,9 @@ jobs: sudo apt-get install pep8 python3-autopep8 python3-pep8 python-is-python3 - name: Check Code Format - run: | - autopep8 srunner/scenariomanager/*.py --in-place --max-line-length=120 --ignore=E731 - autopep8 srunner/scenariomanager/scenarioatomics/*.py --in-place --max-line-length=120 - autopep8 srunner/scenarios/*.py --in-place --max-line-length=120 - autopep8 srunner/tools/*.py --in-place --max-line-length=120 - autopep8 srunner/scenarioconfigs/*.py --in-place --max-line-length=120 - autopep8 scenario_runner.py --in-place --max-line-length=120 - autopep8 srunner/autoagents/*.py --in-place --max-line-length=120 - git diff --quiet HEAD --; if [ ! $? -eq 0 ]; then echo "Code is not autopep8 compliant. Please run code_check_and_formatting.sh"; git diff HEAD --; exit 1; fi + uses: peter-evans/autopep8@v2 + with: + args: --max-line-length=120 --ignore=E731 --recursive --in-place . qualityJob: name: Check Code Quality @@ -58,4 +52,4 @@ jobs: score=`pylint --rcfile=.pylintrc --disable=I srunner/tools | grep -i "rated at" | awk '{print $7}'`; if [ "$score" != "10.00/10" ]; then static_code_quality_passed=0; fi score=`pylint --rcfile=.pylintrc --disable=I srunner/scenarioconfigs | grep -i "rated at" | awk '{print $7}'`; if [ "$score" != "10.00/10" ]; then static_code_quality_passed=0; fi score=`pylint --rcfile=.pylintrc --disable=I scenario_runner.py | grep -i "rated at" | awk '{print $7}'`; if [ "$score" != "10.00/10" ]; then static_code_quality_passed=0; fi - if [ $static_code_quality_passed -eq 0 ]; then echo "Code is not pylint compliant. Please run code_check_and_formatting.sh"; exit 1; fi \ No newline at end of file + if [ $static_code_quality_passed -eq 0 ]; then echo "Code is not pylint compliant. Please run code_check_and_formatting.sh"; exit 1; fi diff --git a/manual_control.py b/manual_control.py index 9a8e6237c..86fdff8ad 100755 --- a/manual_control.py +++ b/manual_control.py @@ -213,6 +213,7 @@ def destroy(self): class KeyboardControl(object): """Class that handles keyboard input.""" + def __init__(self, world, start_in_autopilot): self._autopilot_enabled = start_in_autopilot self._control = carla.VehicleControl() @@ -277,7 +278,7 @@ def parse_events(self, client, world, clock): self._control.manual_gear_shift = not self._control.manual_gear_shift self._control.gear = world.player.get_control().gear world.hud.notification('%s Transmission' % - ('Manual' if self._control.manual_gear_shift else 'Automatic')) + ('Manual' if self._control.manual_gear_shift else 'Automatic')) elif self._control.manual_gear_shift and event.key == K_COMMA: self._control.gear = max(-1, self._control.gear - 1) elif self._control.manual_gear_shift and event.key == K_PERIOD: @@ -321,13 +322,13 @@ def parse_events(self, client, world, clock): # Set automatic control-related vehicle lights if self._control.brake: current_lights |= carla.VehicleLightState.Brake - else: # Remove the Brake flag + else: # Remove the Brake flag current_lights &= ~carla.VehicleLightState.Brake if self._control.reverse: current_lights |= carla.VehicleLightState.Reverse - else: # Remove the Reverse flag + else: # Remove the Reverse flag current_lights &= ~carla.VehicleLightState.Reverse - if current_lights != self._lights: # Change the light state only if necessary + if current_lights != self._lights: # Change the light state only if necessary self._lights = current_lights world.player.set_light_state(carla.VehicleLightState(self._lights)) world.player.apply_control(self._control) @@ -536,6 +537,7 @@ def render(self, display): class HelpText(object): """Helper class to handle text output using pygame""" + def __init__(self, font, width, height): lines = __doc__.split('\n') self.font = font @@ -709,7 +711,7 @@ def __init__(self, parent_actor): bound_y = 0.5 + self._parent.bounding_box.extent.y bound_z = 0.5 + self._parent.bounding_box.extent.z - self.velocity_range = 7.5 # m/s + self.velocity_range = 7.5 # m/s world = self._parent.get_world() self.debug = world.debug bp = world.get_blueprint_library().find('sensor.other.radar') @@ -718,7 +720,7 @@ def __init__(self, parent_actor): self.sensor = world.spawn_actor( bp, carla.Transform( - carla.Location(x=bound_x + 0.05, z=bound_z+0.05), + carla.Location(x=bound_x + 0.05, z=bound_z + 0.05), carla.Rotation(pitch=5)), attach_to=self._parent) # We need a weak reference to self to avoid circular reference. @@ -752,7 +754,7 @@ def _Radar_callback(weak_self, radar_data): def clamp(min_v, max_v, value): return max(min_v, min(value, max_v)) - norm_velocity = detect.velocity / self.velocity_range # range [-1, 1] + norm_velocity = detect.velocity / self.velocity_range # range [-1, 1] r = int(clamp(0.0, 1.0, 1.0 - norm_velocity) * 255.0) g = int(clamp(0.0, 1.0, 1.0 - abs(norm_velocity)) * 255.0) b = int(abs(clamp(- 1.0, 0.0, - 1.0 - norm_velocity)) * 255.0) @@ -781,11 +783,13 @@ def __init__(self, parent_actor, hud): Attachment = carla.AttachmentType self._camera_transforms = [ - (carla.Transform(carla.Location(x=-2.0*bound_x, y=+0.0*bound_y, z=2.0*bound_z), carla.Rotation(pitch=8.0)), Attachment.SpringArm), - (carla.Transform(carla.Location(x=+0.8*bound_x, y=+0.0*bound_y, z=1.3*bound_z)), Attachment.Rigid), - (carla.Transform(carla.Location(x=+1.9*bound_x, y=+1.0*bound_y, z=1.2*bound_z)), Attachment.SpringArm), - (carla.Transform(carla.Location(x=-2.8*bound_x, y=+0.0*bound_y, z=4.6*bound_z), carla.Rotation(pitch=6.0)), Attachment.SpringArm), - (carla.Transform(carla.Location(x=-1.0, y=-1.0*bound_y, z=0.4*bound_z)), Attachment.Rigid)] + (carla.Transform(carla.Location(x=-2.0 * bound_x, y=+0.0 * bound_y, + z=2.0 * bound_z), carla.Rotation(pitch=8.0)), Attachment.SpringArm), + (carla.Transform(carla.Location(x=+0.8 * bound_x, y=+0.0 * bound_y, z=1.3 * bound_z)), Attachment.Rigid), + (carla.Transform(carla.Location(x=+1.9 * bound_x, y=+1.0 * bound_y, z=1.2 * bound_z)), Attachment.SpringArm), + (carla.Transform(carla.Location(x=-2.8 * bound_x, y=+0.0 * bound_y, + z=4.6 * bound_z), carla.Rotation(pitch=6.0)), Attachment.SpringArm), + (carla.Transform(carla.Location(x=-1.0, y=-1.0 * bound_y, z=0.4 * bound_z)), Attachment.Rigid)] self.transform_index = 1 self.sensors = [['sensor.camera.rgb', cc.Raw, 'Camera RGB']] @@ -894,7 +898,7 @@ def game_loop(args): display = pygame.display.set_mode( (args.width, args.height), pygame.HWSURFACE | pygame.DOUBLEBUF) - display.fill((0,0,0)) + display.fill((0, 0, 0)) pygame.display.flip() hud = HUD(args.width, args.height) diff --git a/metrics_manager.py b/metrics_manager.py index 3cdea4c4b..c5e3c7ef9 100644 --- a/metrics_manager.py +++ b/metrics_manager.py @@ -130,10 +130,11 @@ def main(): """ # pylint: disable=line-too-long - description = ("Scenario Runner's metrics module. Evaluate the execution of a specific scenario by developing your own metric.\n") + description = ( + "Scenario Runner's metrics module. Evaluate the execution of a specific scenario by developing your own metric.\n") parser = argparse.ArgumentParser(description=description, - formatter_class=RawTextHelpFormatter) + formatter_class=RawTextHelpFormatter) parser.add_argument('--host', default='127.0.0.1', help='IP of the host server (default: localhost)') parser.add_argument('--port', '-p', default=2000, @@ -150,5 +151,6 @@ def main(): MetricsManager(args) + if __name__ == "__main__": sys.exit(main()) diff --git a/no_rendering_mode.py b/no_rendering_mode.py index ec24d1dab..7397ec112 100755 --- a/no_rendering_mode.py +++ b/no_rendering_mode.py @@ -1415,6 +1415,7 @@ def game_loop(args): if world_module is not None: world_module.destroy() + def exit_game(): module_manager.clear_modules() pygame.quit() @@ -1490,5 +1491,6 @@ def main(): game_loop(args) + if __name__ == '__main__': main() diff --git a/scenario_runner.py b/scenario_runner.py index 5f0e8e79a..7aa2baedd 100755 --- a/scenario_runner.py +++ b/scenario_runner.py @@ -23,7 +23,7 @@ try: from packaging.version import Version except ImportError: - from distutils.version import LooseVersion as Version # Python 2 fallback + from distutils.version import LooseVersion as Version # Python 2 fallback import importlib import inspect import os @@ -35,12 +35,18 @@ try: # requires Python 3.8+ from importlib.metadata import metadata + def get_carla_version(): + """get the version of the CARLA package + """ return Version(metadata("carla")["Version"]) except ModuleNotFoundError: # backport checking for older Python versions; module is deprecated import pkg_resources + def get_carla_version(): + """same but for older Python versions + """ return Version(pkg_resources.get_distribution("carla").version) import carla @@ -106,7 +112,8 @@ def __init__(self, args): self.client.set_timeout(self.client_timeout) carla_version = get_carla_version() if carla_version < Version(MIN_CARLA_VERSION): - raise ImportError("CARLA version {} or newer required. CARLA version found: {}".format(MIN_CARLA_VERSION, carla_version)) + raise ImportError("CARLA version {} or newer required. CARLA version found: {}".format( + MIN_CARLA_VERSION, carla_version)) # Load agent if requested via command line args # If something goes wrong an exception will be thrown by importlib (ok here) @@ -660,4 +667,4 @@ def main(): if __name__ == "__main__": - sys.exit(main()) \ No newline at end of file + sys.exit(main()) diff --git a/srunner/metrics/examples/basic_metric.py b/srunner/metrics/examples/basic_metric.py index 331f48eaf..ac921361b 100644 --- a/srunner/metrics/examples/basic_metric.py +++ b/srunner/metrics/examples/basic_metric.py @@ -10,6 +10,7 @@ This module provide BasicMetric, the basic class of all the metrics. """ + class BasicMetric(object): """ Base class of all the metrics. diff --git a/srunner/metrics/examples/criteria_filter.py b/srunner/metrics/examples/criteria_filter.py index e1eacf25e..e6b0c830c 100644 --- a/srunner/metrics/examples/criteria_filter.py +++ b/srunner/metrics/examples/criteria_filter.py @@ -34,13 +34,13 @@ def _create_metric(self, town_map, log, criteria): for criterion_name in criteria: criterion = criteria[criterion_name] results.update({criterion_name: - { - "test_status": criterion["test_status"], - "actual_value": criterion["actual_value"], - "success_value": criterion["success_value"] - } - } - ) + { + "test_status": criterion["test_status"], + "actual_value": criterion["actual_value"], + "success_value": criterion["success_value"] + } + } + ) with open('srunner/metrics/data/CriteriaFilter_results.json', 'w') as fw: json.dump(results, fw, sort_keys=False, indent=4) diff --git a/srunner/metrics/examples/distance_to_lane_center.py b/srunner/metrics/examples/distance_to_lane_center.py index 3916096ae..88a2bbeed 100644 --- a/srunner/metrics/examples/distance_to_lane_center.py +++ b/srunner/metrics/examples/distance_to_lane_center.py @@ -50,7 +50,7 @@ def _create_metric(self, town_map, log, criteria): b_norm = math.sqrt(b.x * b.x + b.y * b.y + b.z * b.z) ab_dot = a.x * b.x + a.y * b.y + a.z * b.z - dist_v = ab_dot/(b_norm*b_norm)*b + dist_v = ab_dot / (b_norm * b_norm) * b dist = math.sqrt(dist_v.x * dist_v.x + dist_v.y * dist_v.y + dist_v.z * dist_v.z) # Get the sign of the distance (left side is positive) diff --git a/srunner/metrics/tools/metrics_log.py b/srunner/metrics/tools/metrics_log.py index 4dce1e532..e58f405b1 100644 --- a/srunner/metrics/tools/metrics_log.py +++ b/srunner/metrics/tools/metrics_log.py @@ -17,6 +17,7 @@ import fnmatch from srunner.metrics.tools.metrics_parser import MetricsParser + class MetricsLog(object): # pylint: disable=too-many-public-methods """ Utility class to query the log. diff --git a/srunner/metrics/tools/metrics_parser.py b/srunner/metrics/tools/metrics_parser.py index e7ea1a9e0..0a37aefc0 100644 --- a/srunner/metrics/tools/metrics_parser.py +++ b/srunner/metrics/tools/metrics_parser.py @@ -26,6 +26,7 @@ def parse_actor(info): } return actor + def parse_transform(info): """Parses a list into a carla.Transform""" transform = carla.Transform( @@ -36,12 +37,13 @@ def parse_transform(info): ), carla.Rotation( roll=float(info[7][1:-1]), - pitch=float(info[8][:-1]), + pitch=float(info[8][:-1]), yaw=float(info[9][:-1]) ) ) return transform + def parse_control(info): """Parses a list into a carla.VehicleControl""" control = carla.VehicleControl( @@ -55,6 +57,7 @@ def parse_control(info): ) return control + def parse_vehicle_lights(info): """Parses a list into a carla.VehicleLightState""" srt_to_vlight = { @@ -78,6 +81,7 @@ def parse_vehicle_lights(info): return lights + def parse_traffic_light(info): """Parses a list into a dictionary with all the traffic light's information""" number_to_state = { @@ -94,6 +98,7 @@ def parse_traffic_light(info): } return traffic_light + def parse_velocity(info): """Parses a list into a carla.Vector3D with the velocity""" velocity = carla.Vector3D( @@ -103,6 +108,7 @@ def parse_velocity(info): ) return velocity + def parse_angular_velocity(info): """Parses a list into a carla.Vector3D with the angular velocity""" velocity = carla.Vector3D( @@ -112,6 +118,7 @@ def parse_angular_velocity(info): ) return velocity + def parse_scene_lights(info): """Parses a list into a carla.VehicleLightState""" @@ -127,6 +134,7 @@ def parse_scene_lights(info): ) return scene_light + def parse_bounding_box(info): """ Parses a list into a carla.BoundingBox. @@ -136,24 +144,25 @@ def parse_bounding_box(info): location = carla.Location() else: location = carla.Location( - float(info[3][1:-1])/100, - float(info[4][:-1])/100, - float(info[5][:-1])/100, + float(info[3][1:-1]) / 100, + float(info[4][:-1]) / 100, + float(info[5][:-1]) / 100, ) if 'inf' in info[7]: extent = carla.Vector3D() else: extent = carla.Vector3D( - float(info[7][1:-1])/100, - float(info[8][:-1])/100, - float(info[9][:-1])/100, + float(info[7][1:-1]) / 100, + float(info[8][:-1]) / 100, + float(info[9][:-1]) / 100, ) bbox = carla.BoundingBox(location, extent) return bbox + def parse_state_times(info): """Parses a list into a dict containing the state times of the traffic lights""" state_times = { @@ -163,18 +172,20 @@ def parse_state_times(info): } return state_times + def parse_vector_list(info): """Parses a list of string into a list of Vector2D""" vector_list = [] for i in range(0, len(info), 2): vector = carla.Vector2D( x=float(info[i][1:-1]), - y=float(info[i+1][:-1]), + y=float(info[i + 1][:-1]), ) vector_list.append(vector) return vector_list + def parse_gears_control(info): """Parses a list into a GearPhysicsControl""" gears_control = carla.GearPhysicsControl( @@ -184,6 +195,7 @@ def parse_gears_control(info): ) return gears_control + def parse_wheels_control(info): """Parses a list into a WheelsPhysicsControl""" wheels_control = carla.WheelPhysicsControl( @@ -283,7 +295,7 @@ def parse_recorder_info(self): "platform_time": None }, "actors": {}, - "events":{ + "events": { "scene_lights": {}, "physics_control": {}, "traffic_light_state_time": {}, diff --git a/srunner/scenarioconfigs/openscenario_configuration.py b/srunner/scenarioconfigs/openscenario_configuration.py index 7bd1b6d6a..cc4927236 100644 --- a/srunner/scenarioconfigs/openscenario_configuration.py +++ b/srunner/scenarioconfigs/openscenario_configuration.py @@ -307,7 +307,7 @@ def _extract_vehicle_information(self, obj, rolename, vehicle, args): speed = self._get_actor_speed(rolename) new_actor = ActorConfigurationData( - model, None, rolename, speed, color=color, category=category, args=args) + model, carla.Transform(), rolename, speed, color=color, category=category, args=args) if ego_vehicle: self.ego_vehicles.append(new_actor) @@ -321,7 +321,7 @@ def _extract_pedestrian_information(self, obj, rolename, pedestrian, args): model = pedestrian.attrib.get('model', "walker.*") speed = self._get_actor_speed(rolename) - new_actor = ActorConfigurationData(model, None, rolename, speed, category="pedestrian", args=args) + new_actor = ActorConfigurationData(model, carla.Transform(), rolename, speed, category="pedestrian", args=args) self.other_actors.append(new_actor) @@ -336,7 +336,7 @@ def _extract_misc_information(self, obj, rolename, misc, args): model = "static.prop.chainbarrier" else: model = misc.attrib.get('name') - new_actor = ActorConfigurationData(model, None, rolename, category="misc", args=args) + new_actor = ActorConfigurationData(model, carla.Transform(), rolename, category="misc", args=args) self.other_actors.append(new_actor) @@ -424,4 +424,3 @@ def _set_traffic_signal_controller(self): controller = rnw.find("TrafficSignals") if controller is not None: OpenScenarioParser.set_traffic_signal_controller(controller) - \ No newline at end of file diff --git a/srunner/scenarioconfigs/osc2_scenario_configuration.py b/srunner/scenarioconfigs/osc2_scenario_configuration.py index ceff63454..582a7659c 100644 --- a/srunner/scenarioconfigs/osc2_scenario_configuration.py +++ b/srunner/scenarioconfigs/osc2_scenario_configuration.py @@ -4,6 +4,8 @@ generate relevant type objects in the standard library, and set parameters """ +from srunner.tools.osc2_helper import OSC2Helper +from srunner.scenariomanager.carla_data_provider import CarlaDataProvider import sys from typing import List, Tuple @@ -27,10 +29,8 @@ ''' # pylint: enable=line-too-long -from srunner.scenariomanager.carla_data_provider import CarlaDataProvider # OSC2 -from srunner.tools.osc2_helper import OSC2Helper vehicle_type = ["Car", "Model3", "Mkz2017", "Carlacola", "Rubicon"] @@ -48,7 +48,7 @@ def flat_list(list_of_lists): class OSC2ScenarioConfiguration(ScenarioConfiguration): def __init__(self, filename, client): super(OSC2ScenarioConfiguration, self).__init__() - + self.name = self.filename = filename self.ast_tree = OSC2Helper.gen_osc2_ast(self.filename) diff --git a/srunner/scenariomanager/actorcontrols/simple_vehicle_control.py b/srunner/scenariomanager/actorcontrols/simple_vehicle_control.py index 5f1d58daa..1bbc0e231 100644 --- a/srunner/scenariomanager/actorcontrols/simple_vehicle_control.py +++ b/srunner/scenariomanager/actorcontrols/simple_vehicle_control.py @@ -241,8 +241,8 @@ def _offset_waypoint(self, transform): offset_location = transform.location else: right_vector = transform.get_right_vector() - offset_location = transform.location + carla.Location(x=self._offset*right_vector.x, - y=self._offset*right_vector.y) + offset_location = transform.location + carla.Location(x=self._offset * right_vector.x, + y=self._offset * right_vector.y) return offset_location diff --git a/srunner/scenariomanager/actorcontrols/visualizer.py b/srunner/scenariomanager/actorcontrols/visualizer.py index 5c0c670c2..5c6f80ae9 100644 --- a/srunner/scenariomanager/actorcontrols/visualizer.py +++ b/srunner/scenariomanager/actorcontrols/visualizer.py @@ -116,12 +116,12 @@ def render(self): if self._cv_image_actor is not None and self._cv_image_bird is not None: im_v = cv2.vconcat([self._cv_image_actor, self._cv_image_bird]) cv2.circle(im_v, (900, 300), 80, (170, 170, 170), -1) - text = str(int(round((self._actor.get_velocity().x * 3.6))))+" kph" + text = str(int(round((self._actor.get_velocity().x * 3.6)))) + " kph" speed = np.sqrt(self._actor.get_velocity().x**2 + self._actor.get_velocity().y**2) - text = str(int(round((speed * 3.6))))+" kph" - text = ' '*(7-len(text)) + text + text = str(int(round((speed * 3.6)))) + " kph" + text = ' ' * (7 - len(text)) + text im_v = cv2.putText(im_v, text, (830, 310), cv2.FONT_HERSHEY_SIMPLEX, 1, (0, 0, 0), 2, cv2.LINE_AA) cv2.imshow("", im_v) cv2.waitKey(1) diff --git a/srunner/scenariomanager/carla_data_provider.py b/srunner/scenariomanager/carla_data_provider.py index 9e5e23d39..7e97f6a03 100644 --- a/srunner/scenariomanager/carla_data_provider.py +++ b/srunner/scenariomanager/carla_data_provider.py @@ -53,7 +53,7 @@ class CarlaDataProvider(object): # pylint: disable=too-many-public-methods _actor_transform_map = {} # type: dict[carla.Actor, carla.Transform] _traffic_light_map = {} # type: dict[carla.TrafficLight, carla.Transform] _carla_actor_pool = {} # type: dict[int, carla.Actor] - _global_osc_parameters = {} # type: dict[str, Any] # type: ignore : suppresses the missing Any import + _global_osc_parameters = {} # type: dict[str, Any] # type: ignore : suppresses the missing Any import _client = None # type: carla.Client _world = None # type: carla.World _map = None # type: carla.Map @@ -415,7 +415,7 @@ def update_light_states(ego_light, annotations, states, freeze=False, timeout=10 """ Update traffic light states """ - reset_params = [] # type: list[dict] + reset_params = [] # type: list[dict] for state in states: relevant_lights = [] @@ -622,7 +622,7 @@ def check_attribute_value(blueprint, name, value): 'train': '', 'tram': '', 'pedestrian': 'walker.pedestrian.0001', - 'misc': 'static.prop.streetbarrier' + 'misc': 'static.prop.streetbarrier' } # Set the model @@ -735,7 +735,7 @@ def spawn_actor(bp, spawn_point, must_spawn=False, track_physics=None, attach_to Returns: carla.Actor | None: The spawned actor if successful, None otherwise. - + Raises: RuntimeError: if `must_spawn` is True and the actor could not be spawned. """ @@ -1004,7 +1004,7 @@ def remove_actor_by_id(actor_id): """ if actor_id in CarlaDataProvider._carla_actor_pool: CarlaDataProvider._carla_actor_pool[actor_id].destroy() - CarlaDataProvider._carla_actor_pool[actor_id] = None # type: ignore + CarlaDataProvider._carla_actor_pool[actor_id] = None # type: ignore CarlaDataProvider._carla_actor_pool.pop(actor_id) else: print("Trying to remove a non-existing actor id {}".format(actor_id)) diff --git a/srunner/scenariomanager/lights_sim.py b/srunner/scenariomanager/lights_sim.py index 316def239..eeda1c95c 100644 --- a/srunner/scenariomanager/lights_sim.py +++ b/srunner/scenariomanager/lights_sim.py @@ -150,4 +150,4 @@ def _turn_all_lights_off(self): def terminate(self, new_status): self._light_manager.set_day_night_cycle(True) - return super().terminate(new_status) \ No newline at end of file + return super().terminate(new_status) diff --git a/srunner/scenariomanager/scenarioatomics/atomic_behaviors.py b/srunner/scenariomanager/scenarioatomics/atomic_behaviors.py index 56b03de0a..1385dd3c5 100644 --- a/srunner/scenariomanager/scenarioatomics/atomic_behaviors.py +++ b/srunner/scenariomanager/scenarioatomics/atomic_behaviors.py @@ -1677,7 +1677,7 @@ def update(self): if self._type == 'vehicle': # curr_speed = CarlaDataProvider.get_velocity(self._actor) - curr_speed = calculate_velocity(self._actor)*3.6 + curr_speed = calculate_velocity(self._actor) * 3.6 if abs(self._target_velocity - curr_speed) < self.OFFSET_THRESHOLD: self._control.throttle = 0 self._control.brake = 0 @@ -2438,7 +2438,7 @@ def __init__(self, actor, target_location=None, plan=None, target_speed=20, opt_ def initialise(self): """Initialises the agent""" self._agent = BasicAgent(self._actor, self._target_speed, opt_dict=self._opt_dict, - map_inst=CarlaDataProvider.get_map(), grp_inst=CarlaDataProvider.get_global_route_planner()) + map_inst=CarlaDataProvider.get_map(), grp_inst=CarlaDataProvider.get_global_route_planner()) if self._plan: self._agent.set_global_plan(self._plan) elif self._target_location: @@ -2531,6 +2531,7 @@ def terminate(self, new_status): self._agent.destroy_sensor() super(ConstantVelocityAgentBehavior, self).terminate(new_status) + class AdaptiveConstantVelocityAgentBehavior(AtomicBehavior): """ @@ -2605,6 +2606,7 @@ def terminate(self, new_status): self._agent.destroy_sensor() super().terminate(new_status) + class Idle(AtomicBehavior): """ @@ -2644,6 +2646,7 @@ def update(self): return new_status + class WaitForever(AtomicBehavior): """ @@ -3516,8 +3519,8 @@ def terminate(self, new_status): # Patched by removing its movement actor.disable_constant_velocity() actor.set_autopilot(False, CarlaDataProvider.get_traffic_manager_port()) - actor.set_target_velocity(carla.Vector3D(0,0,0)) - actor.set_target_angular_velocity(carla.Vector3D(0,0,0)) + actor.set_target_velocity(carla.Vector3D(0, 0, 0)) + actor.set_target_angular_velocity(carla.Vector3D(0, 0, 0)) try: actor.destroy() except RuntimeError: @@ -3597,7 +3600,7 @@ def _move_waypoint_backwards(self, wp, distance): def initialise(self): """Get the actor flow source and sink, depending on the reference actor speed""" - self._speed = self._reference_actor.get_speed_limit() # Km / h + self._speed = self._reference_actor.get_speed_limit() # Km / h self._flow_distance = self._time_distance * self._speed + self._base_distance self._sink_wp = self._move_waypoint_forward(self._reference_wp, self._flow_distance) @@ -3665,8 +3668,8 @@ def terminate(self, new_status): # Patched by removing its movement actor.disable_constant_velocity() actor.set_autopilot(False, CarlaDataProvider.get_traffic_manager_port()) - actor.set_target_velocity(carla.Vector3D(0,0,0)) - actor.set_target_angular_velocity(carla.Vector3D(0,0,0)) + actor.set_target_velocity(carla.Vector3D(0, 0, 0)) + actor.set_target_angular_velocity(carla.Vector3D(0, 0, 0)) try: actor.destroy() except RuntimeError: @@ -3698,7 +3701,7 @@ def __init__(self, source_wp, sink_wp, reference_actor, spawn_dist, self._reference_actor = reference_actor - self._source_wp = source_wp + self._source_wp = source_wp self._source_transform = self._source_wp.transform self._source_location = self._source_transform.location @@ -3780,8 +3783,8 @@ def terminate(self, new_status): # Patched by removing its movement actor.disable_constant_velocity() actor.set_autopilot(False, CarlaDataProvider.get_traffic_manager_port()) - actor.set_target_velocity(carla.Vector3D(0,0,0)) - actor.set_target_angular_velocity(carla.Vector3D(0,0,0)) + actor.set_target_velocity(carla.Vector3D(0, 0, 0)) + actor.set_target_angular_velocity(carla.Vector3D(0, 0, 0)) try: actor.destroy() except RuntimeError: @@ -3869,7 +3872,7 @@ def _spawn_actor(self, transform): return controller = BasicAgent(actor, 3.6 * self._speed, opt_dict=self._opt_dict, - map_inst=CarlaDataProvider.get_map(), grp_inst=CarlaDataProvider.get_global_route_planner()) + map_inst=CarlaDataProvider.get_map(), grp_inst=CarlaDataProvider.get_global_route_planner()) controller.set_global_plan(plan) initial_vec = plan[0][0].transform.get_forward_vector() @@ -3923,8 +3926,8 @@ def terminate(self, new_status): # Patched by removing its movement actor.disable_constant_velocity() actor.set_autopilot(False, CarlaDataProvider.get_traffic_manager_port()) - actor.set_target_velocity(carla.Vector3D(0,0,0)) - actor.set_target_angular_velocity(carla.Vector3D(0,0,0)) + actor.set_target_velocity(carla.Vector3D(0, 0, 0)) + actor.set_target_angular_velocity(carla.Vector3D(0, 0, 0)) try: actor.destroy() except RuntimeError: @@ -4544,11 +4547,11 @@ def update(self): if is_within_distance(ref_actor_transform, actor_transform, float('inf'), [0, 90]) and \ operator.le(gap, self._gap): try: - factor = abs(actor_velocity - reference_velocity)/actor_velocity + factor = abs(actor_velocity - reference_velocity) / actor_velocity if actor_velocity > reference_velocity: - actor_velocity = actor_velocity - (factor*actor_velocity) + actor_velocity = actor_velocity - (factor * actor_velocity) elif actor_velocity < reference_velocity and operator.gt(gap, self._gap): - actor_velocity = actor_velocity + (factor*actor_velocity) + actor_velocity = actor_velocity + (factor * actor_velocity) except ZeroDivisionError: pass actor_dict[self._actor.id].update_target_speed(actor_velocity) @@ -4653,6 +4656,7 @@ class WalkerFlow(AtomicBehavior): - sink_distance: Actors closer to the sink than this distance will be deleted. Probably due to the navigation module rerouting the walkers, a sink distance of 2 is reasonable. """ + def __init__(self, source_location, sink_locations, sink_locations_prob, spawn_dist_interval, random_seed=None, sink_dist=2, name="WalkerFlow"): """ @@ -4678,7 +4682,7 @@ def __init__(self, source_location, sink_locations, sink_locations_prob, spawn_d self._max_spawn_dist = spawn_dist_interval[1] self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist) - self._batch_size_list = [1,2,3] + self._batch_size_list = [1, 2, 3] self._walkers = [] @@ -4712,7 +4716,7 @@ def update(self): continue # Use ai.walker to controll walkers controller = self._world.try_spawn_actor(self._controller_bp, carla.Transform(), walker) - sink_location = self._rng.choice(a = self._sink_locations, p = self._sink_locations_prob) + sink_location = self._rng.choice(a=self._sink_locations, p=self._sink_locations_prob) controller.start() controller.go_to_location(sink_location) # Add to walkers list @@ -4737,6 +4741,7 @@ def terminate(self, new_status): except RuntimeError: pass # Actor was already destroyed + class AIWalkerBehavior(AtomicBehavior): """ Behavior that creates a walker controlled by AI Walker controller. @@ -4869,7 +4874,8 @@ def terminate(self, new_status): Modifies the blackboard to tell the `ScenarioTimeoutTest` if the timeout was triggered """ if not self._terminated: # py_trees calls the terminate several times for some reason. - py_trees.blackboard.Blackboard().set(f"ScenarioTimeout_{self._scenario_name}", self._scenario_timeout, overwrite=True) + py_trees.blackboard.Blackboard().set( + f"ScenarioTimeout_{self._scenario_name}", self._scenario_timeout, overwrite=True) py_trees.blackboard.Blackboard().set("AC_SwitchActorBlockedTest", True, overwrite=True) self._terminated = True super().terminate(new_status) diff --git a/srunner/scenariomanager/scenarioatomics/atomic_criteria.py b/srunner/scenariomanager/scenarioatomics/atomic_criteria.py index 45dc96115..78eaa1d0d 100644 --- a/srunner/scenariomanager/scenarioatomics/atomic_criteria.py +++ b/srunner/scenariomanager/scenarioatomics/atomic_criteria.py @@ -369,7 +369,7 @@ def _count_collisions(self, event): # pylint: disable=too-many-return-statem if "traffic" not in event.other_actor.type_id and "static" not in event.other_actor.type_id: return elif self._other_actor_type not in event.other_actor.type_id: - return + return # To avoid multiple counts of the same collision, filter some of them. if self._collision_id == event.other_actor.id: @@ -389,7 +389,7 @@ def _count_collisions(self, event): # pylint: disable=too-many-return-statem self._collision_time = GameTime.get_time() self._collision_location = actor_location - if event.other_actor.id != 0: # Number 0: static objects -> ignore it + if event.other_actor.id != 0: # Number 0: static objects -> ignore it self._collision_id = event.other_actor.id if ('static' in event.other_actor.type_id or 'traffic' in event.other_actor.type_id) \ @@ -892,7 +892,8 @@ def update(self): self.actual_value += 1 - onsidewalk_event = TrafficEvent(event_type=TrafficEventType.ON_SIDEWALK_INFRACTION, frame=GameTime.get_frame()) + onsidewalk_event = TrafficEvent( + event_type=TrafficEventType.ON_SIDEWALK_INFRACTION, frame=GameTime.get_frame()) self._set_event_message( onsidewalk_event, self._sidewalk_start_location, self._wrong_sidewalk_distance) self._set_event_dict( @@ -907,7 +908,8 @@ def update(self): self.actual_value += 1 - outsidelane_event = TrafficEvent(event_type=TrafficEventType.OUTSIDE_LANE_INFRACTION, frame=GameTime.get_frame()) + outsidelane_event = TrafficEvent( + event_type=TrafficEventType.OUTSIDE_LANE_INFRACTION, frame=GameTime.get_frame()) self._set_event_message( outsidelane_event, self._outside_lane_start_location, self._wrong_outside_lane_distance) self._set_event_dict( @@ -930,7 +932,8 @@ def terminate(self, new_status): self.actual_value += 1 - onsidewalk_event = TrafficEvent(event_type=TrafficEventType.ON_SIDEWALK_INFRACTION, frame=GameTime.get_frame()) + onsidewalk_event = TrafficEvent( + event_type=TrafficEventType.ON_SIDEWALK_INFRACTION, frame=GameTime.get_frame()) self._set_event_message( onsidewalk_event, self._sidewalk_start_location, self._wrong_sidewalk_distance) self._set_event_dict( @@ -945,7 +948,8 @@ def terminate(self, new_status): self.actual_value += 1 - outsidelane_event = TrafficEvent(event_type=TrafficEventType.OUTSIDE_LANE_INFRACTION, frame=GameTime.get_frame()) + outsidelane_event = TrafficEvent( + event_type=TrafficEventType.OUTSIDE_LANE_INFRACTION, frame=GameTime.get_frame()) self._set_event_message( outsidelane_event, self._outside_lane_start_location, self._wrong_outside_lane_distance) self._set_event_dict( @@ -1084,7 +1088,8 @@ def _set_traffic_event(self): Creates the traffic event / updates it """ if self._traffic_event is None: - self._traffic_event = TrafficEvent(event_type=TrafficEventType.OUTSIDE_ROUTE_LANES_INFRACTION, frame=GameTime.get_frame()) + self._traffic_event = TrafficEvent( + event_type=TrafficEventType.OUTSIDE_ROUTE_LANES_INFRACTION, frame=GameTime.get_frame()) self.events.append(self._traffic_event) percentage = self._wrong_distance / self._total_distance * 100 @@ -1369,7 +1374,8 @@ def update(self): if self.test_status != "SUCCESS": in_radius = math.sqrt(((location.x - self._x)**2) + ((location.y - self._y)**2)) < self._radius if in_radius: - route_completion_event = TrafficEvent(event_type=TrafficEventType.ROUTE_COMPLETED, frame=GameTime.get_frame()) + route_completion_event = TrafficEvent( + event_type=TrafficEventType.ROUTE_COMPLETED, frame=GameTime.get_frame()) route_completion_event.set_message("Destination was successfully reached") self.events.append(route_completion_event) self.test_status = "SUCCESS" @@ -1491,7 +1497,8 @@ def update(self): blackv = py_trees.blackboard.Blackboard() _ = blackv.set("InRoute", False) - route_deviation_event = TrafficEvent(event_type=TrafficEventType.ROUTE_DEVIATION, frame=GameTime.get_frame()) + route_deviation_event = TrafficEvent( + event_type=TrafficEventType.ROUTE_DEVIATION, frame=GameTime.get_frame()) route_deviation_event.set_message( "Agent deviated from the route at (x={}, y={}, z={})".format( round(location.x, 3), @@ -1728,7 +1735,8 @@ def update(self): self.test_status = "FAILURE" self.actual_value += 1 location = traffic_light.get_transform().location - red_light_event = TrafficEvent(event_type=TrafficEventType.TRAFFIC_LIGHT_INFRACTION, frame=GameTime.get_frame()) + red_light_event = TrafficEvent( + event_type=TrafficEventType.TRAFFIC_LIGHT_INFRACTION, frame=GameTime.get_frame()) red_light_event.set_message( "Agent ran a red light {} at (x={}, y={}, z={})".format( traffic_light.id, @@ -1806,7 +1814,7 @@ class RunningStopTest(Criterion): - terminate_on_failure [optional]: If True, the complete scenario will terminate upon failure of this test """ PROXIMITY_THRESHOLD = 4.0 # Stops closer than this distance will be detected [m] - SPEED_THRESHOLD = 0.1 # Minimum speed to consider the actor has stopped [m/s] + SPEED_THRESHOLD = 0.1 # Minimum speed to consider the actor has stopped [m/s] WAYPOINT_STEP = 0.5 # m def __init__(self, actor, name="RunningStopTest", terminate_on_failure=False): @@ -1929,7 +1937,8 @@ def update(self): self.actual_value += 1 self.test_status = "FAILURE" stop_location = self._target_stop_sign.get_transform().location - running_stop_event = TrafficEvent(event_type=TrafficEventType.STOP_INFRACTION, frame=GameTime.get_frame()) + running_stop_event = TrafficEvent( + event_type=TrafficEventType.STOP_INFRACTION, frame=GameTime.get_frame()) running_stop_event.set_message( "Agent ran a stop with id={} at (x={}, y={}, z={})".format( self._target_stop_sign.id, @@ -1999,7 +2008,6 @@ def __init__(self, actor, route, checkpoints=1, name="MinimumSpeedRouteTest", te self._index = 0 - def update(self): """ Check if the actor location is within trigger region @@ -2009,7 +2017,7 @@ def update(self): if self._terminate_on_failure and (self.test_status == "FAILURE"): new_status = py_trees.common.Status.FAILURE - # Check the actor progress through the route + # Check the actor progress through the route location = CarlaDataProvider.get_location(self.actor) if location is None: return new_status @@ -2102,7 +2110,7 @@ class YieldToEmergencyVehicleTest(Criterion): optional (bool): If True, the result is not considered for an overall pass/fail result """ - WAITING_TIME_THRESHOLD = 15 # Maximum time for actor to block ev + WAITING_TIME_THRESHOLD = 15 # Maximum time for actor to block ev def __init__(self, actor, ev, optional=False, name="YieldToEmergencyVehicleTest"): """ diff --git a/srunner/scenarios/actor_flow.py b/srunner/scenarios/actor_flow.py index 88a461f2c..e669cf165 100644 --- a/srunner/scenarios/actor_flow.py +++ b/srunner/scenarios/actor_flow.py @@ -31,6 +31,7 @@ RemoveRoadLane) from srunner.tools.scenario_helper import get_same_dir_lanes, generate_target_waypoint_in_route + def convert_dict_to_location(actor_dict): """ Convert a JSON string to a Carla.Location @@ -42,12 +43,14 @@ def convert_dict_to_location(actor_dict): ) return location + def get_value_parameter(config, name, p_type, default): if name in config.other_parameters: return p_type(config.other_parameters[name]['value']) else: return default + def get_interval_parameter(config, name, p_type, default): if name in config.other_parameters: return [ @@ -57,6 +60,7 @@ def get_interval_parameter(config, name, p_type, default): else: return default + class EnterActorFlow(BasicScenario): """ This class holds everything required for a scenario in which another vehicle runs a red light @@ -109,7 +113,8 @@ def _create_behavior(self): policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) for source_wp, sink_wp in zip(source_wps, sink_wps): - root.add_child(InTriggerDistanceToLocation(self.ego_vehicles[0], sink_wp.transform.location, self._sink_distance)) + root.add_child(InTriggerDistanceToLocation( + self.ego_vehicles[0], sink_wp.transform.location, self._sink_distance)) root.add_child(ActorFlow( source_wp, sink_wp, self._source_dist_interval, self._sink_distance, self._flow_speed, initial_actors=True, initial_junction=True)) @@ -120,9 +125,9 @@ def _create_behavior(self): grp = CarlaDataProvider.get_global_route_planner() route = grp.trace_route(source_wp.transform.location, sink_wp.transform.location) extra_space = 20 - for i in range(-2, -len(route)-1, -1): + for i in range(-2, -len(route) - 1, -1): current_wp = route[i][0] - extra_space += current_wp.transform.location.distance(route[i+1][0].transform.location) + extra_space += current_wp.transform.location.distance(route[i + 1][0].transform.location) if current_wp.is_junction: break @@ -162,6 +167,7 @@ class EnterActorFlowV2(EnterActorFlow): """ Variation of EnterActorFlow for special highway entry exits with dedicated lanes """ + def _create_behavior(self): """ Hero vehicle is entering a junction in an urban area, at a signalized intersection, @@ -176,10 +182,11 @@ def _create_behavior(self): root = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) root.add_child(ActorFlow( - source_wp, sink_wp, self._source_dist_interval, self._sink_distance, - self._flow_speed, initial_actors=True, initial_junction=True)) + source_wp, sink_wp, self._source_dist_interval, self._sink_distance, + self._flow_speed, initial_actors=True, initial_junction=True)) for sink_wp in sink_wps: - root.add_child(InTriggerDistanceToLocation(self.ego_vehicles[0], sink_wp.transform.location, self._sink_distance)) + root.add_child(InTriggerDistanceToLocation( + self.ego_vehicles[0], sink_wp.transform.location, self._sink_distance)) root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name)) exit_wp = generate_target_waypoint_in_route(self._reference_waypoint, self.config.route) @@ -189,9 +196,9 @@ def _create_behavior(self): grp = CarlaDataProvider.get_global_route_planner() route = grp.trace_route(source_wp.transform.location, sink_wp.transform.location) self._extra_space = 20 - for i in range(-2, -len(route)-1, -1): + for i in range(-2, -len(route) - 1, -1): current_wp = route[i][0] - self._extra_space += current_wp.transform.location.distance(route[i+1][0].transform.location) + self._extra_space += current_wp.transform.location.distance(route[i + 1][0].transform.location) if current_wp.is_junction: break @@ -214,7 +221,7 @@ def _create_behavior(self): clear_junction=False, clear_ego_entry=True, remove_entries=[source_wp], - remove_exits= get_same_dir_lanes(exit_wp), + remove_exits=get_same_dir_lanes(exit_wp), stop_entries=False, extend_road_exit=0 )) @@ -337,7 +344,7 @@ def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=Fals self._start_actor_flow = convert_dict_to_location(config.other_parameters['start_actor_flow']) self._end_actor_flow = convert_dict_to_location(config.other_parameters['end_actor_flow']) - self._trigger_point=config.trigger_points[0].location + self._trigger_point = config.trigger_points[0].location self._sink_distance = 2 @@ -365,7 +372,8 @@ def _create_behavior(self): root = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) for wp in sink_wps: - root.add_child(InTriggerDistanceToLocation(self.ego_vehicles[0], wp.transform.location, self._sink_distance)) + root.add_child(InTriggerDistanceToLocation( + self.ego_vehicles[0], wp.transform.location, self._sink_distance)) root.add_child(ActorFlow( source_wp, sink_wp, self._source_dist_interval, self._sink_distance, self._flow_speed, initial_actors=True, initial_junction=True)) @@ -377,9 +385,9 @@ def _create_behavior(self): grp = CarlaDataProvider.get_global_route_planner() route = grp.trace_route(source_wp.transform.location, sink_wp.transform.location) extra_space = 0 - for i in range(-2, -len(route)-1, -1): + for i in range(-2, -len(route) - 1, -1): current_wp = route[i][0] - extra_space += current_wp.transform.location.distance(route[i+1][0].transform.location) + extra_space += current_wp.transform.location.distance(route[i + 1][0].transform.location) if current_wp.is_junction: break @@ -435,7 +443,8 @@ def _create_behavior(self): source_wp, sink_wp, self._source_dist_interval, self._sink_distance, self._flow_speed, initial_actors=True, initial_junction=True)) for sink_wp in sink_wps: - root.add_child(InTriggerDistanceToLocation(self.ego_vehicles[0], sink_wp.transform.location, self._sink_distance)) + root.add_child(InTriggerDistanceToLocation( + self.ego_vehicles[0], sink_wp.transform.location, self._sink_distance)) root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name)) exit_wp = generate_target_waypoint_in_route(self._reference_waypoint, self.config.route) @@ -445,9 +454,9 @@ def _create_behavior(self): grp = CarlaDataProvider.get_global_route_planner() route = grp.trace_route(source_wp.transform.location, sink_wp.transform.location) self._extra_space = 20 - for i in range(-2, -len(route)-1, -1): + for i in range(-2, -len(route) - 1, -1): current_wp = route[i][0] - self._extra_space += current_wp.transform.location.distance(route[i+1][0].transform.location) + self._extra_space += current_wp.transform.location.distance(route[i + 1][0].transform.location) if current_wp.is_junction: break @@ -552,7 +561,7 @@ def _get_entry_exit_route_lanes(self, wp, route): # Enter the junction if not reached_junction and (road_option in (RoadOption.LEFT, RoadOption.RIGHT, RoadOption.STRAIGHT)): reached_junction = True - entry_wp = self._map.get_waypoint(route[i-1][0].location) + entry_wp = self._map.get_waypoint(route[i - 1][0].location) entry_wp = entry_wp.previous(2)[0] # Just in case # End condition for the behavior, at the end of the junction @@ -563,7 +572,6 @@ def _get_entry_exit_route_lanes(self, wp, route): return (entry_wp, exit_wp) - def _create_behavior(self): """ Create an actor flow at the opposite lane which the ego has to cross @@ -667,7 +675,7 @@ def _get_junction_exit_wp(self, exit_wp): return exit_wp def _initialize_actors(self, config): - + self._source_wp_1 = self._map.get_waypoint(self._start_actor_flow_1) self._sink_wp_1 = self._map.get_waypoint(self._end_actor_flow_1) @@ -683,9 +691,9 @@ def _initialize_actors(self, config): route = grp.trace_route(self._source_wp_2.transform.location, self._sink_wp_2.transform.location) self._extra_space = 20 route_exit_wp = None - for i in range(-2, -len(route)-1, -1): + for i in range(-2, -len(route) - 1, -1): current_wp = route[i][0] - self._extra_space += current_wp.transform.location.distance(route[i+1][0].transform.location) + self._extra_space += current_wp.transform.location.distance(route[i + 1][0].transform.location) if current_wp.is_junction: junction = current_wp.get_junction() break diff --git a/srunner/scenarios/background_activity.py b/srunner/scenarios/background_activity.py index fdacf5663..2a01f13a5 100644 --- a/srunner/scenarios/background_activity.py +++ b/srunner/scenarios/background_activity.py @@ -28,20 +28,24 @@ EGO_JUNCTION = 'junction' EGO_ROAD = 'road' + def get_lane_key(waypoint): """Returns a key corresponding to the waypoint lane. Equivalent to a 'Lane' object and used to compare waypoint lanes""" return '' if waypoint is None else get_road_key(waypoint) + '*' + str(waypoint.lane_id) + def get_road_key(waypoint): """Returns a key corresponding to the waypoint road. Equivalent to a 'Road' object and used to compare waypoint roads""" return '' if waypoint is None else str(waypoint.road_id) + def is_lane_at_road(lane_key, road_key): """Returns whether or not a lane is part of a road""" return lane_key.startswith(road_key) + def get_lane_key_from_ids(road_id, lane_id): """Returns the lane corresping to a given road and lane ids""" return str(road_id) + '*' + str(lane_id) @@ -74,6 +78,7 @@ def get_lane_key_from_ids(road_id, lane_id): DEBUG_LARGE: [0.2, 0.2], } # Size, height + def draw_string(world, location, string='', debug_type=DEBUG_ROAD, persistent=False): """Utility function to draw debugging strings""" v_shift, _ = DEBUG_TYPE.get(DEBUG_SMALL) @@ -82,6 +87,7 @@ def draw_string(world, location, string='', debug_type=DEBUG_ROAD, persistent=Fa life_time = 0.06 if not persistent else 100000 world.debug.draw_string(location + l_shift, string, False, color, life_time) + def draw_point(world, location, point_type=DEBUG_SMALL, debug_type=DEBUG_ROAD, persistent=False): """Utility function to draw debugging points""" v_shift, size = DEBUG_TYPE.get(point_type, DEBUG_SMALL) @@ -90,6 +96,7 @@ def draw_point(world, location, point_type=DEBUG_SMALL, debug_type=DEBUG_ROAD, p life_time = 0.06 if not persistent else 100000 world.debug.draw_point(location + l_shift, size, color, life_time) + def draw_arrow(world, location1, location2, arrow_type=DEBUG_SMALL, debug_type=DEBUG_ROAD, persistent=False): """Utility function to draw debugging points""" if location1 == location2: @@ -145,7 +152,7 @@ def __init__(self, junction, junction_id, route_entry_index=None, route_exit_ind self.exit_dict = OrderedDict() self.actor_dict = OrderedDict() - # Junction scenario variables + # Junction scenario variables self.stop_non_route_entries = False self.clear_middle = False self.inactive_entry_keys = [] @@ -303,7 +310,7 @@ def update(self): prev_ego_index = self._route_index # Check if the TM destroyed an actor - if self._route_index > 0: # TODO: This check is due to intialization problem + if self._route_index > 0: # TODO: This check is due to intialization problem self._check_background_actors() # Update ego's route position. For robustness, the route point is used for most calculus @@ -381,13 +388,13 @@ def _get_junctions_data(self): break for i in range(start_index, self._route_length - 1): - next_wp = self._route[i+1] + next_wp = self._route[i + 1] prev_junction = junction_data[-1] if len(junction_data) > 0 else None # Searching for the junction exit if prev_junction and prev_junction.route_exit_index is None: if not self._is_junction(next_wp) or next_wp.get_junction().id != junction_id: - prev_junction.route_exit_index = i+1 + prev_junction.route_exit_index = i + 1 # Searching for a junction elif self._is_junction(next_wp): @@ -421,7 +428,7 @@ def _filter_fake_junctions(self, data): filtered_data = [] for junction_data in data: - if len (junction_data.junctions) > 1: + if len(junction_data.junctions) > 1: filtered_data.append(junction_data) continue # These are always junctions @@ -917,7 +924,7 @@ def _end_junction_behavior(self, junction): self._road_dict[exit_key].actors.append(actor) else: entry_sources = self._active_junctions[0].entry_sources - for entry_source in entry_sources: # Add it to the back source + for entry_source in entry_sources: # Add it to the back source if exit_key == get_lane_key(entry_source.wp): entry_sources.actors.append(actor) break @@ -1031,7 +1038,7 @@ def _move_road_sources(self, prev_ego_index): for lane_key in self._road_dict: source = self._road_dict[lane_key] - # If no actors are found, let the last_location be ego's location + # If no actors are found, let the last_location be ego's location # to keep moving the source waypoint forward if len(source.actors) == 0: last_location = self._ego_wp.transform.location @@ -1302,7 +1309,8 @@ def _update_junction_sources(self): for source in junction.entry_sources: if self.debug: draw_point(self._world, source.wp.transform.location, DEBUG_SMALL, DEBUG_JUNCTION, False) - draw_string(self._world, source.wp.transform.location, str(len(source.actors)), DEBUG_JUNCTION, False) + draw_string(self._world, source.wp.transform.location, + str(len(source.actors)), DEBUG_JUNCTION, False) entry_lane_key = get_lane_key(source.entry_lane_wp) at_oppo_entry_lane = entry_lane_key in junction.opposite_entry_keys @@ -1431,14 +1439,16 @@ def get_source_wp(wp): if get_lane_key(source_wp) not in self._road_dict: # Lanes created away from the center won't affect the ids of other lanes, so just add the new id - self._road_dict[get_lane_key(source_wp)] = Source(source_wp, actors, active=self._active_road_sources) + self._road_dict[get_lane_key(source_wp)] = Source( + source_wp, actors, active=self._active_road_sources) else: # If the lane is inwards, all lanes have their id shifted by 1 outwards # TODO: Doesn't work for more than one lane. added_id = 1 if source_wp.lane_id > 0 else -1 new_lane_key = get_lane_key_from_ids(source_wp.road_id, source_wp.lane_id + added_id) self._road_dict[new_lane_key] = self._road_dict[get_lane_key(source_wp)] - self._road_dict[get_lane_key(source_wp)] = Source(source_wp, actors, active=self._active_road_sources) + self._road_dict[get_lane_key(source_wp)] = Source( + source_wp, actors, active=self._active_road_sources) elif len(new_wps) < len(old_wps): for old_wp in list(old_wps): @@ -2264,7 +2274,7 @@ def _monitor_road_changes(self, prev_route_index): def get_lane_waypoints(reference_wp, index=0): if not reference_wp.is_junction: wps = get_same_dir_lanes(reference_wp) - else: # Handle fake junction by using its entry / exit wps + else: # Handle fake junction by using its entry / exit wps wps = [] for junction_wps in reference_wp.get_junction().get_waypoints(carla.LaneType.Driving): if get_road_key(junction_wps[index]) == get_road_key(reference_wp): @@ -2349,7 +2359,8 @@ def is_road_dict_unchanging(wp_pairs): continue if self.debug: - draw_arrow(self._world, old_wp.transform.location, new_wp.transform.location, DEBUG_MEDIUM, DEBUG_ROAD, True) + draw_arrow(self._world, old_wp.transform.location, + new_wp.transform.location, DEBUG_MEDIUM, DEBUG_ROAD, True) # Check that the lane is part of the road dictionary if old_key in list(self._road_dict): @@ -2403,7 +2414,7 @@ def _update_junction_actors(self): state, exit_lane_key, _ = actor_dict[actor].values() if self.debug: - string = 'J' + str(i+1) + '_' + state[:2] + string = 'J' + str(i + 1) + '_' + state[:2] draw_string(self._world, location, string, DEBUG_JUNCTION, False) # Special scenario actors. Treat them as road actors @@ -2427,13 +2438,13 @@ def _update_junction_actors(self): if i < max_index and actor_lane_key in junction.route_exit_keys: # Exited through a connecting lane in the route direction. self._remove_actor_info(actor) - other_junction = self._active_junctions[i+1] + other_junction = self._active_junctions[i + 1] self._add_actor_dict_element(other_junction.actor_dict, actor) elif i > 0 and actor_lane_key in junction.opposite_exit_keys: # Exited through a connecting lane in the opposite direction. # THIS SHOULD NEVER HAPPEN, an entry source should have already added it. - other_junction = self._active_junctions[i-1] + other_junction = self._active_junctions[i - 1] if actor not in other_junction.actor_dict: self._remove_actor_info(actor) self._add_actor_dict_element(other_junction.actor_dict, actor, at_oppo_entry_lane=True) @@ -2576,15 +2587,15 @@ def _update_ego_data(self): if self._scenario_removed_lane: for i in range(prev_index, self._route_index): option_1 = self._route_options[i] - option_2 = self._route_options[i+1] + option_2 = self._route_options[i + 1] if option_1 == RoadOption.CHANGELANELEFT or option_2 == RoadOption.CHANGELANELEFT: loc_1 = self._route[i].transform.location - loc_2 = self._route[i+1].transform.location + loc_2 = self._route[i + 1].transform.location if abs(loc_1.distance(loc_2)) > 2.5: # Lane offset plus a bit forward self._scenario_remove_lane_offset += 1 elif option_1 == RoadOption.CHANGELANERIGHT or option_2 == RoadOption.CHANGELANERIGHT: loc_1 = self._route[i].transform.location - loc_2 = self._route[i+1].transform.location + loc_2 = self._route[i + 1].transform.location if abs(loc_1.distance(loc_2)) > 2.5: # Lane offset plus a bit forward self._scenario_remove_lane_offset -= 1 diff --git a/srunner/scenarios/background_activity_parametrizer.py b/srunner/scenarios/background_activity_parametrizer.py index f11b8e7b7..9de835026 100644 --- a/srunner/scenarios/background_activity_parametrizer.py +++ b/srunner/scenarios/background_activity_parametrizer.py @@ -16,12 +16,14 @@ ChangeOppositeBehavior, ChangeJunctionBehavior) + def get_parameter(config, name): if name in config.other_parameters: return float(config.other_parameters[name]['value']) else: return None + class BackgroundActivityParametrizer(BasicScenario): """ This class holds everything required to change the parameters of the background activity. @@ -53,11 +55,11 @@ def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=Fals self._junction_source_perc = get_parameter(config, "junction_source_perc") super().__init__("BackgroundActivityParametrizer", - ego_vehicles, - config, - world, - debug_mode, - criteria_enable=criteria_enable) + ego_vehicles, + config, + world, + debug_mode, + criteria_enable=criteria_enable) def _create_behavior(self): """ @@ -86,4 +88,3 @@ def __del__(self): Remove all actors and traffic lights upon deletion """ self.remove_all_actors() - diff --git a/srunner/scenarios/basic_scenario.py b/srunner/scenarios/basic_scenario.py index 39c3adf10..0031d14db 100644 --- a/srunner/scenarios/basic_scenario.py +++ b/srunner/scenarios/basic_scenario.py @@ -53,7 +53,7 @@ def __init__(self, name, ego_vehicles, config, world, # If no timeout was provided, set it to 60 seconds if not hasattr(self, 'timeout'): - self.timeout = 60 + self.timeout = 60 if debug_mode: py_trees.logging.level = py_trees.logging.Level.DEBUG diff --git a/srunner/scenarios/construction_crash_vehicle.py b/srunner/scenarios/construction_crash_vehicle.py index da1cc7769..67351d60f 100644 --- a/srunner/scenarios/construction_crash_vehicle.py +++ b/srunner/scenarios/construction_crash_vehicle.py @@ -36,6 +36,7 @@ def get_value_parameter(config, name, p_type, default): else: return default + def get_interval_parameter(config, name, p_type, default): if name in config.other_parameters: return [ @@ -45,6 +46,7 @@ def get_interval_parameter(config, name, p_type, default): else: return default + class ConstructionObstacle(BasicScenario): """ This class holds everything required for a construction scenario @@ -226,7 +228,7 @@ def _create_behavior(self): for actor, transform in self._construction_transforms: root.add_child(ActorTransformSetter(actor, transform, True)) - + end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name)) end_condition.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._end_wp.transform, False)) @@ -271,6 +273,7 @@ class ConstructionObstacleTwoWays(ConstructionObstacle): """ Variation of ConstructionObstacle where the ego has to invade the opposite lane """ + def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60): self._opposite_interval = get_interval_parameter(config, 'frequency', float, [20, 100]) @@ -292,7 +295,7 @@ def _create_behavior(self): for actor, transform in self._construction_transforms: root.add_child(ActorTransformSetter(actor, transform, True)) - + end_condition = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) end_condition.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name)) end_condition.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._end_wp.transform, False)) diff --git a/srunner/scenarios/cross_bicycle_flow.py b/srunner/scenarios/cross_bicycle_flow.py index fd13bf310..a051815bd 100644 --- a/srunner/scenarios/cross_bicycle_flow.py +++ b/srunner/scenarios/cross_bicycle_flow.py @@ -52,6 +52,7 @@ def get_interval_parameter(config, name, p_type, default): else: return default + class CrossingBicycleFlow(BasicScenario): """ This class holds everything required for a scenario in which another vehicle runs a red light @@ -153,7 +154,6 @@ def _get_traffic_lights(self, tls, ego_dist): self._flow_tl_dict[tl] = carla.TrafficLightState.Red self._init_tl_dict[tl] = carla.TrafficLightState.Red - def _create_behavior(self): """ Hero vehicle is entering a junction in an urban area, at a signalized intersection, diff --git a/srunner/scenarios/cut_in_with_static_vehicle.py b/srunner/scenarios/cut_in_with_static_vehicle.py index 01d345bfd..65dacc243 100644 --- a/srunner/scenarios/cut_in_with_static_vehicle.py +++ b/srunner/scenarios/cut_in_with_static_vehicle.py @@ -57,7 +57,7 @@ def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=Fals self._front_vehicles = 3 self._vehicle_gap = 11 - self._speed = 60 # Km/h + self._speed = 60 # Km/h self._adversary_end_distance = 70 @@ -159,8 +159,8 @@ def _initialize_actors(self, config): self._side_transforms.append([self._adversary_actor, side_wp.transform]) self.other_actors.append(self._adversary_actor) - # This starts the engine, to allow the adversary to instantly move - self._adversary_actor.apply_control(carla.VehicleControl(throttle=1.0, brake=1.0)) + # This starts the engine, to allow the adversary to instantly move + self._adversary_actor.apply_control(carla.VehicleControl(throttle=1.0, brake=1.0)) # Move to the front next_wps = blocker_wp.next(self._vehicle_gap) diff --git a/srunner/scenarios/highway_cut_in.py b/srunner/scenarios/highway_cut_in.py index 1a0fac4f3..8a98552ec 100644 --- a/srunner/scenarios/highway_cut_in.py +++ b/srunner/scenarios/highway_cut_in.py @@ -27,6 +27,7 @@ from srunner.tools.scenario_helper import generate_target_waypoint + def convert_dict_to_location(actor_dict): """ Convert a JSON string to a Carla.Location @@ -38,6 +39,7 @@ def convert_dict_to_location(actor_dict): ) return location + class HighwayCutIn(BasicScenario): """ This class holds everything required for a scenario in which another vehicle runs a red light @@ -88,7 +90,6 @@ def _initialize_actors(self, config): self._cut_in_vehicle.set_location(self._other_transform.location - carla.Location(z=100)) self._cut_in_vehicle.set_simulate_physics(False) - def _create_behavior(self): """ Hero vehicle is entering a junction in an urban area, at a signalized intersection, diff --git a/srunner/scenarios/invading_turn.py b/srunner/scenarios/invading_turn.py index cda71841e..09d2cd182 100644 --- a/srunner/scenarios/invading_turn.py +++ b/srunner/scenarios/invading_turn.py @@ -67,8 +67,8 @@ def __init__(self, world, ego_vehicles, config, debug_mode=False, criteria_enabl self._reference_waypoint = self._map.get_waypoint( self._trigger_location) - self._flow_frequency = 40 # m - self._source_dist = 30 # Distance between source and end point + self._flow_frequency = 40 # m + self._source_dist = 30 # Distance between source and end point self._check_distance = 50 @@ -105,7 +105,7 @@ def _initialize_actors(self, config): # Lane offset self._offset_constant = 0.7 # Ideally, half the vehicle lane width self._true_offset = self._offset + self._sink_wp.lane_width / 2 - self._offset_constant - self._true_offset *= -1 # Cause left direction + self._true_offset *= -1 # Cause left direction self._create_obstacle() @@ -152,7 +152,8 @@ def _create_behavior(self): main_behavior.add_child(InvadingActorFlow( self._source_wp, self._sink_wp, self.ego_vehicles[0], self._flow_frequency, offset=self._true_offset)) - main_behavior.add_child(WaitUntilInFrontPosition(self.ego_vehicles[0], self._forward_wp.transform, True, self._check_distance)) + main_behavior.add_child(WaitUntilInFrontPosition( + self.ego_vehicles[0], self._forward_wp.transform, True, self._check_distance)) main_behavior.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name)) sequence.add_child(main_behavior) diff --git a/srunner/scenarios/object_crash_vehicle.py b/srunner/scenarios/object_crash_vehicle.py index 485705ade..5075c3339 100644 --- a/srunner/scenarios/object_crash_vehicle.py +++ b/srunner/scenarios/object_crash_vehicle.py @@ -493,7 +493,7 @@ def _initialize_actors(self, config): walker.set_location(self._walker_transform.location + carla.Location(z=-200)) walker = self._replace_walker(walker) - + self.other_actors.append(walker) self._collision_wp = walker_wp diff --git a/srunner/scenarios/open_scenario.py b/srunner/scenarios/open_scenario.py index 135375779..f9a8afefa 100644 --- a/srunner/scenarios/open_scenario.py +++ b/srunner/scenarios/open_scenario.py @@ -333,7 +333,7 @@ def _create_init_behavior(self): self.config.catalogs) atomic = ChangeActorWaypoints(carla_actor, waypoints=list( zip(waypoints, ['shortest'] * len(waypoints))), - times=times, name="FollowTrajectoryAction") + times=times, name="FollowTrajectoryAction") elif private_action.find('AcquirePositionAction') is not None: route_action = private_action.find('AcquirePositionAction') osc_position = route_action.find('Position') @@ -430,7 +430,7 @@ def _create_behavior(self): maneuver_behavior = StoryElementStatusToBlackboard( maneuver_behavior, "ACTION", child.attrib.get('name')) parallel_actions.add_child( - oneshot_with_check(variable_name= # See note in get_xml_path + oneshot_with_check(variable_name=# See note in get_xml_path get_xml_path(story, sequence) + '>' + \ get_xml_path(maneuver, child) + '>' + \ str(actor_id), diff --git a/srunner/scenarios/opposite_vehicle_taking_priority.py b/srunner/scenarios/opposite_vehicle_taking_priority.py index 3bf945d61..27ddbf2f2 100644 --- a/srunner/scenarios/opposite_vehicle_taking_priority.py +++ b/srunner/scenarios/opposite_vehicle_taking_priority.py @@ -35,7 +35,6 @@ from srunner.tools.background_manager import HandleJunctionScenario - class OppositeVehicleJunction(BasicScenario): """ Scenario in which another vehicle enters the junction a tthe same time as the ego, @@ -52,14 +51,13 @@ def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=Fals self._map = CarlaDataProvider.get_map() self._source_dist = 30 self._sink_dist = 10 - self._adversary_speed = 60 / 3.6 # m/s + self._adversary_speed = 60 / 3.6 # m/s if 'direction' in config.other_parameters: self._direction = config.other_parameters['direction']['value'] else: self._direction = "right" - self.timeout = timeout self._sync_time = 2.2 # Time the agent has to react to avoid the collision [s] diff --git a/srunner/scenarios/parking_cut_in.py b/srunner/scenarios/parking_cut_in.py index 30c8fee63..00ea412e5 100644 --- a/srunner/scenarios/parking_cut_in.py +++ b/srunner/scenarios/parking_cut_in.py @@ -122,9 +122,9 @@ def _get_displaced_location(self, actor, wp): if self._direction == 'left': displacement_vector *= -1 - new_location = wp.transform.location + carla.Location(x=displacement*displacement_vector.x, - y=displacement*displacement_vector.y, - z=displacement*displacement_vector.z) + new_location = wp.transform.location + carla.Location(x=displacement * displacement_vector.x, + y=displacement * displacement_vector.y, + z=displacement * displacement_vector.z) new_location.z += 0.05 # Just in case, avoid collisions with the ground return new_location diff --git a/srunner/scenarios/parking_exit.py b/srunner/scenarios/parking_exit.py index acbb69643..0ed0d7dec 100644 --- a/srunner/scenarios/parking_exit.py +++ b/srunner/scenarios/parking_exit.py @@ -175,9 +175,9 @@ def _get_displaced_location(self, actor, wp): if self._direction == 'left': displacement_vector *= -1 - new_location = wp.transform.location + carla.Location(x=displacement*displacement_vector.x, - y=displacement*displacement_vector.y, - z=displacement*displacement_vector.z) + new_location = wp.transform.location + carla.Location(x=displacement * displacement_vector.x, + y=displacement * displacement_vector.y, + z=displacement * displacement_vector.z) new_location.z += 0.05 # Just in case, avoid collisions with the ground return new_location diff --git a/srunner/scenarios/pedestrian_crossing.py b/srunner/scenarios/pedestrian_crossing.py index 6cb70c2de..50f524647 100644 --- a/srunner/scenarios/pedestrian_crossing.py +++ b/srunner/scenarios/pedestrian_crossing.py @@ -77,11 +77,11 @@ def __init__(self, world, ego_vehicles, config, debug_mode=False, criteria_enabl walker_data['speed'] = self._rng.uniform(1.3, 2.0) super().__init__("PedestrianCrossing", - ego_vehicles, - config, - world, - debug_mode, - criteria_enable=criteria_enable) + ego_vehicles, + config, + world, + debug_mode, + criteria_enable=criteria_enable) def _get_walker_transform(self, wp, displacement): disp_x = displacement['x'] diff --git a/srunner/scenarios/route_obstacles.py b/srunner/scenarios/route_obstacles.py index 8a0a3dc11..5de34f414 100644 --- a/srunner/scenarios/route_obstacles.py +++ b/srunner/scenarios/route_obstacles.py @@ -39,6 +39,7 @@ def get_value_parameter(config, name, p_type, default): else: return default + def get_interval_parameter(config, name, p_type, default): if name in config.other_parameters: return [ @@ -65,7 +66,7 @@ def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=Fals self._world = world self._map = CarlaDataProvider.get_map() self.timeout = timeout - + self._first_distance = 10 self._second_distance = 6 @@ -238,6 +239,7 @@ class AccidentTwoWays(Accident): """ Variation of the Accident scenario but the ego now has to invade the opposite lane """ + def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=180): self._opposite_interval = get_interval_parameter(config, 'frequency', float, [20, 100]) @@ -281,6 +283,7 @@ def _create_behavior(self): return root + class ParkedObstacle(BasicScenario): """ Scenarios in which a parked vehicle is incorrectly parked, @@ -443,6 +446,7 @@ class ParkedObstacleTwoWays(ParkedObstacle): """ Variation of the ParkedObstacle scenario but the ego now has to invade the opposite lane """ + def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=180): self._opposite_interval = get_interval_parameter(config, 'frequency', float, [20, 100]) @@ -613,7 +617,8 @@ def _create_behavior(self): opt_dict = {'offset': offset} for actor, target_loc in zip(self.other_actors, self._target_locs): bicycle = py_trees.composites.Sequence(name="Bicycle behavior") - bicycle.add_child(BasicAgentBehavior(actor, target_loc, target_speed=self._bicycle_speed, opt_dict=opt_dict)) + bicycle.add_child(BasicAgentBehavior(actor, target_loc, + target_speed=self._bicycle_speed, opt_dict=opt_dict)) bicycle.add_child(HandBrakeVehicle(actor, 1)) # In case of collisions bicycle.add_child(WaitForever()) # Don't make the bicycle stop the parallel behavior main_behavior.add_child(bicycle) @@ -659,6 +664,7 @@ class HazardAtSideLaneTwoWays(HazardAtSideLane): """ Variation of the HazardAtSideLane scenario but the ego now has to invade the opposite lane """ + def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=180): self._opposite_frequency = get_value_parameter(config, 'frequency', float, 100) @@ -691,7 +697,8 @@ def _create_behavior(self): opt_dict = {'offset': offset} for actor, target_loc in zip(self.other_actors, self._target_locs): bicycle = py_trees.composites.Sequence(name="Bicycle behavior") - bicycle.add_child(BasicAgentBehavior(actor, target_loc, target_speed=self._bicycle_speed, opt_dict=opt_dict)) + bicycle.add_child(BasicAgentBehavior(actor, target_loc, + target_speed=self._bicycle_speed, opt_dict=opt_dict)) bicycle.add_child(HandBrakeVehicle(actor, 1)) # In case of collisions bicycle.add_child(WaitForever()) # Don't make the bicycle stop the parallel behavior main_behavior.add_child(bicycle) diff --git a/srunner/scenarios/route_scenario.py b/srunner/scenarios/route_scenario.py index 9835f1109..5fd830954 100644 --- a/srunner/scenarios/route_scenario.py +++ b/srunner/scenarios/route_scenario.py @@ -71,7 +71,8 @@ def __init__(self, world, config, debug_mode=False, criteria_enable=True, timeou self.timeout = self._estimate_route_timeout() if debug_mode: - self._draw_waypoints(world, self.route, vertical_shift=0.1, size=0.1, persistency=self.timeout, downsample=5) + self._draw_waypoints(world, self.route, vertical_shift=0.1, size=0.1, + persistency=self.timeout, downsample=5) self._build_scenarios( world, ego_vehicle, sampled_scenario_definitions, timeout=self.timeout, debug=debug_mode > 0 @@ -167,9 +168,9 @@ def _draw_waypoints(self, world, waypoints, vertical_shift, size, persistency=-1 world.debug.draw_point(wp, size=0.1, color=color, life_time=persistency) - world.debug.draw_point(waypoints[0][0].location + carla.Location(z=vertical_shift), size=2*size, + world.debug.draw_point(waypoints[0][0].location + carla.Location(z=vertical_shift), size=2 * size, color=carla.Color(0, 0, 128), life_time=persistency) - world.debug.draw_point(waypoints[-1][0].location + carla.Location(z=vertical_shift), size=2*size, + world.debug.draw_point(waypoints[-1][0].location + carla.Location(z=vertical_shift), size=2 * size, color=carla.Color(128, 128, 128), life_time=persistency) def _scenario_sampling(self, potential_scenarios, random_seed=0): @@ -245,8 +246,8 @@ def _build_scenarios(self, world, ego_vehicle, scenario_definitions, scenarios_p self.list_scenarios.append(scenario_instance) - # pylint: enable=no-self-use + def _initialize_actors(self, config): """ Set other_actors to the superset of all scenario actors @@ -305,7 +306,8 @@ def _create_test_criteria(self): criteria.add_child(CollisionTest(self.ego_vehicles[0], name="CollisionTest")) criteria.add_child(RunningRedLightTest(self.ego_vehicles[0])) criteria.add_child(RunningStopTest(self.ego_vehicles[0])) - criteria.add_child(MinimumSpeedRouteTest(self.ego_vehicles[0], route=self.route, checkpoints=4, name="MinSpeedTest")) + criteria.add_child(MinimumSpeedRouteTest( + self.ego_vehicles[0], route=self.route, checkpoints=4, name="MinSpeedTest")) # These stop the route early to save computational time criteria.add_child(InRouteTest( @@ -367,7 +369,7 @@ def _create_criterion_tree(self, scenario, criteria): criteria_tree.add_child(WaitForBlackboardVariable(var_name, True, False, name=check_name)) scenario_criteria = py_trees.composites.Parallel(name=scenario_name, - policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) + policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) for criterion in criteria: scenario_criteria.add_child(criterion) scenario_criteria.add_child(WaitForBlackboardVariable(var_name, False, None, name=check_name)) @@ -376,7 +378,6 @@ def _create_criterion_tree(self, scenario, criteria): criteria_tree.add_child(Idle()) # Avoid the indivual criteria stopping the simulation return criteria_tree - def __del__(self): """ Remove all actors upon deletion diff --git a/srunner/scenarios/signalized_junction_left_turn.py b/srunner/scenarios/signalized_junction_left_turn.py index 0bb4ae308..413b48a54 100644 --- a/srunner/scenarios/signalized_junction_left_turn.py +++ b/srunner/scenarios/signalized_junction_left_turn.py @@ -27,12 +27,14 @@ from srunner.tools.background_manager import HandleJunctionScenario, ChangeOppositeBehavior + def get_value_parameter(config, name, p_type, default): if name in config.other_parameters: return p_type(config.other_parameters[name]['value']) else: return default + def get_interval_parameter(config, name, p_type, default): if name in config.other_parameters: return [ diff --git a/srunner/scenarios/signalized_junction_right_turn.py b/srunner/scenarios/signalized_junction_right_turn.py index f8843ec5d..def50b22d 100644 --- a/srunner/scenarios/signalized_junction_right_turn.py +++ b/srunner/scenarios/signalized_junction_right_turn.py @@ -35,6 +35,7 @@ def get_value_parameter(config, name, p_type, default): else: return default + def get_interval_parameter(config, name, p_type, default): if name in config.other_parameters: return [ diff --git a/srunner/scenarios/vehicle_opens_door.py b/srunner/scenarios/vehicle_opens_door.py index 1f226e3b3..6e31e2bce 100644 --- a/srunner/scenarios/vehicle_opens_door.py +++ b/srunner/scenarios/vehicle_opens_door.py @@ -55,6 +55,7 @@ class VehicleOpensDoorTwoWays(BasicScenario): This class holds everything required for a scenario in which another vehicle parked at the side lane opens the door, forcing the ego to lane change, invading the opposite lane """ + def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=180): """ @@ -93,9 +94,9 @@ def _get_displaced_location(self, actor, wp): if self._direction == 'right': displacement_vector *= -1 - new_location = wp.transform.location + carla.Location(x=displacement*displacement_vector.x, - y=displacement*displacement_vector.y, - z=displacement*displacement_vector.z) + new_location = wp.transform.location + carla.Location(x=displacement * displacement_vector.x, + y=displacement * displacement_vector.y, + z=displacement * displacement_vector.z) new_location.z += 0.05 # Just in case, avoid collisions with the ground return new_location diff --git a/srunner/scenarios/yield_to_emergency_vehicle.py b/srunner/scenarios/yield_to_emergency_vehicle.py index f77750e14..34c66c99b 100644 --- a/srunner/scenarios/yield_to_emergency_vehicle.py +++ b/srunner/scenarios/yield_to_emergency_vehicle.py @@ -65,7 +65,7 @@ def __init__(self, world, ego_vehicles, config, debug_mode=False, criteria_enabl self._opt_dict = { 'base_vehicle_threshold': 10, 'detection_speed_ratio': 0.15, 'use_bbs_detection': True, 'base_min_distance': 1, 'distance_ratio': 0.2 - } + } self._trigger_location = config.trigger_points[0].location self._reference_waypoint = self._map.get_waypoint(self._trigger_location) @@ -111,7 +111,7 @@ def _create_behavior(self): """ Spawn the EV behind and wait for it to be close-by. After it has approached, give the ego a certain amount of time to yield to it. - + Sequence: - RemoveRoadLane - ActorTransformSetter diff --git a/srunner/tests/carla_mocks/agents/navigation/behavior_agent.py b/srunner/tests/carla_mocks/agents/navigation/behavior_agent.py index 59c9f03cc..234481800 100644 --- a/srunner/tests/carla_mocks/agents/navigation/behavior_agent.py +++ b/srunner/tests/carla_mocks/agents/navigation/behavior_agent.py @@ -17,6 +17,7 @@ from agents.tools.misc import get_speed, positive, is_within_distance, compute_distance + class BehaviorAgent(BasicAgent): """ BehaviorAgent implements an agent that navigates scenes to reach a given @@ -372,4 +373,4 @@ def emergency_stop(self): control.throttle = 0.0 control.brake = self._max_brake control.hand_brake = False - return control \ No newline at end of file + return control diff --git a/srunner/tests/carla_mocks/agents/navigation/constant_velocity_agent.py b/srunner/tests/carla_mocks/agents/navigation/constant_velocity_agent.py new file mode 100644 index 000000000..27b45ac68 --- /dev/null +++ b/srunner/tests/carla_mocks/agents/navigation/constant_velocity_agent.py @@ -0,0 +1,130 @@ +# Copyright (c) # Copyright (c) 2018-2020 CVC. +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . + +""" +This module implements an agent that roams around a track following random +waypoints and avoiding other vehicles. The agent also responds to traffic lights. +It can also make use of the global route planner to follow a specifed route +""" + +import carla + +from agents.navigation.basic_agent import BasicAgent + + +class ConstantVelocityAgent(BasicAgent): + """ + ConstantVelocityAgent implements an agent that navigates the scene at a fixed velocity. + This agent will fail if asked to perform turns that are impossible are the desired speed. + This includes lane changes. When a collision is detected, the constant velocity will stop, + wait for a bit, and then start again. + """ + + def __init__(self, vehicle, target_speed=20, opt_dict={}, map_inst=None, grp_inst=None): + """ + Initialization the agent parameters, the local and the global planner. + + :param vehicle: actor to apply to agent logic onto + :param target_speed: speed (in Km/h) at which the vehicle will move + :param opt_dict: dictionary in case some of its parameters want to be changed. + This also applies to parameters related to the LocalPlanner. + :param map_inst: carla.Map instance to avoid the expensive call of getting it. + :param grp_inst: GlobalRoutePlanner instance to avoid the expensive call of getting it. + """ + super().__init__(vehicle, target_speed, opt_dict=opt_dict, map_inst=map_inst, grp_inst=grp_inst) + + self._use_basic_behavior = False # Whether or not to use the BasicAgent behavior when the constant velocity is down + self._target_speed = target_speed / 3.6 # [m/s] + self._current_speed = vehicle.get_velocity().length() # [m/s] + self._constant_velocity_stop_time = None + self._collision_sensor = None + + self._restart_time = float('inf') # Time after collision before the constant velocity behavior starts again + + if 'restart_time' in opt_dict: + self._restart_time = opt_dict['restart_time'] + if 'use_basic_behavior' in opt_dict: + self._use_basic_behavior = opt_dict['use_basic_behavior'] + + self.is_constant_velocity_active = True + self._set_collision_sensor() + self._set_constant_velocity(target_speed) + + def set_target_speed(self, speed): + """Changes the target speed of the agent [km/h]""" + self._target_speed = speed / 3.6 + self._local_planner.set_speed(speed) + + def stop_constant_velocity(self): + """Stops the constant velocity behavior""" + self.is_constant_velocity_active = False + self._vehicle.disable_constant_velocity() + self._constant_velocity_stop_time = self._world.get_snapshot().timestamp.elapsed_seconds + + def restart_constant_velocity(self): + """Public method to restart the constant velocity""" + self.is_constant_velocity_active = True + self._set_constant_velocity(self._target_speed) + + def _set_constant_velocity(self, speed): + """Forces the agent to drive at the specified speed""" + self._vehicle.enable_constant_velocity(carla.Vector3D(speed, 0, 0)) + + def run_step(self): + """Execute one step of navigation.""" + if not self.is_constant_velocity_active: + if self._world.get_snapshot().timestamp.elapsed_seconds - self._constant_velocity_stop_time > self._restart_time: + self.restart_constant_velocity() + self.is_constant_velocity_active = True + elif self._use_basic_behavior: + return super(ConstantVelocityAgent, self).run_step() + else: + return carla.VehicleControl() + + hazard_detected = False + + # Retrieve all relevant actors + actor_list = self._world.get_actors() + vehicle_list = actor_list.filter("*vehicle*") + lights_list = actor_list.filter("*traffic_light*") + + vehicle_speed = self._vehicle.get_velocity().length() + + max_vehicle_distance = self._base_vehicle_threshold + vehicle_speed + affected_by_vehicle, adversary, _ = self._vehicle_obstacle_detected(vehicle_list, max_vehicle_distance) + if affected_by_vehicle: + vehicle_velocity = self._vehicle.get_velocity() + if vehicle_velocity.length() == 0: + hazard_speed = 0 + else: + hazard_speed = vehicle_velocity.dot(adversary.get_velocity()) / vehicle_velocity.length() + hazard_detected = True + + # Check if the vehicle is affected by a red traffic light + max_tlight_distance = self._base_tlight_threshold + 0.3 * vehicle_speed + affected_by_tlight, _ = self._affected_by_traffic_light(lights_list, max_tlight_distance) + if affected_by_tlight: + hazard_speed = 0 + hazard_detected = True + + # The longitudinal PID is overwritten by the constant velocity but it is + # still useful to apply it so that the vehicle isn't moving with static wheels + control = self._local_planner.run_step() + if hazard_detected: + self._set_constant_velocity(hazard_speed) + else: + self._set_constant_velocity(self._target_speed) + + return control + + def _set_collision_sensor(self): + blueprint = self._world.get_blueprint_library().find('sensor.other.collision') + self._collision_sensor = self._world.spawn_actor(blueprint, carla.Transform(), attach_to=self._vehicle) + self._collision_sensor.listen(lambda event: self.stop_constant_velocity()) + + def destroy_sensor(self): + if self._collision_sensor: + self._collision_sensor.destroy() + self._collision_sensor = None diff --git a/srunner/tests/carla_mocks/agents/navigation/controller.py b/srunner/tests/carla_mocks/agents/navigation/controller.py index a61803a9f..e40acbd61 100644 --- a/srunner/tests/carla_mocks/agents/navigation/controller.py +++ b/srunner/tests/carla_mocks/agents/navigation/controller.py @@ -19,7 +19,6 @@ class VehiclePIDController(): low level control a vehicle from client side """ - def __init__(self, vehicle, args_lateral, args_longitudinal, offset=0, max_throttle=0.75, max_brake=0.3, max_steering=0.8): """ @@ -91,7 +90,6 @@ def run_step(self, target_speed, waypoint): return control - def change_longitudinal_PID(self, args_longitudinal): """Changes the parameters of the PIDLongitudinalController""" self._lon_controller.change_parameters(**args_longitudinal) @@ -222,8 +220,8 @@ def _pid_control(self, waypoint, vehicle_transform): # Displace the wp to the side w_tran = waypoint.transform r_vec = w_tran.get_right_vector() - w_loc = w_tran.location + carla.Location(x=self._offset*r_vec.x, - y=self._offset*r_vec.y) + w_loc = w_tran.location + carla.Location(x=self._offset * r_vec.x, + y=self._offset * r_vec.y) else: w_loc = waypoint.transform.location @@ -255,4 +253,4 @@ def change_parameters(self, K_P, K_I, K_D, dt): self._k_p = K_P self._k_i = K_I self._k_d = K_D - self._dt = dt \ No newline at end of file + self._dt = dt diff --git a/srunner/tests/carla_mocks/agents/navigation/global_route_planner.py b/srunner/tests/carla_mocks/agents/navigation/global_route_planner.py index 2e7f73af8..0c177c8b7 100644 --- a/srunner/tests/carla_mocks/agents/navigation/global_route_planner.py +++ b/srunner/tests/carla_mocks/agents/navigation/global_route_planner.py @@ -16,6 +16,7 @@ from agents.navigation.local_planner import RoadOption from agents.tools.misc import vector + class GlobalRoutePlanner(object): """ This class provides a very high level route plan. @@ -50,7 +51,7 @@ def trace_route(self, origin, destination): for i in range(len(route) - 1): road_option = self._turn_decision(i, route) - edge = self._graph.edges[route[i], route[i+1]] + edge = self._graph.edges[route[i], route[i + 1]] path = [] if edge['type'] != RoadOption.LANEFOLLOW and edge['type'] != RoadOption.VOID: @@ -60,7 +61,7 @@ def trace_route(self, origin, destination): next_edge = self._graph.edges[n1, n2] if next_edge['path']: closest_index = self._find_closest_in_list(current_waypoint, next_edge['path']) - closest_index = min(len(next_edge['path'])-1, closest_index+5) + closest_index = min(len(next_edge['path']) - 1, closest_index + 5) current_waypoint = next_edge['path'][closest_index] else: current_waypoint = next_edge['exit_waypoint'] @@ -72,9 +73,9 @@ def trace_route(self, origin, destination): for waypoint in path[closest_index:]: current_waypoint = waypoint route_trace.append((current_waypoint, road_option)) - if len(route)-i <= 2 and waypoint.transform.location.distance(destination) < 2*self._sampling_resolution: + if len(route) - i <= 2 and waypoint.transform.location.distance(destination) < 2 * self._sampling_resolution: break - elif len(route)-i <= 2 and current_waypoint.road_id == destination_waypoint.road_id and current_waypoint.section_id == destination_waypoint.section_id and current_waypoint.lane_id == destination_waypoint.lane_id: + elif len(route) - i <= 2 and current_waypoint.road_id == destination_waypoint.road_id and current_waypoint.section_id == destination_waypoint.section_id and current_waypoint.lane_id == destination_waypoint.lane_id: destination_index = self._find_closest_in_list(destination_waypoint, path) if closest_index > destination_index: break @@ -192,7 +193,7 @@ def _find_loose_ends(self): if section_id not in self._road_id_to_edge[road_id]: self._road_id_to_edge[road_id][section_id] = dict() n1 = self._id_map[exit_xyz] - n2 = -1*count_loose_ends + n2 = -1 * count_loose_ends self._road_id_to_edge[road_id][section_id][lane_id] = (n1, n2) next_wp = end_wp.next(hop_resolution) path = [] @@ -276,7 +277,7 @@ def _distance_heuristic(self, n1, n2): """ l1 = np.array(self._graph.nodes[n1]['vertex']) l2 = np.array(self._graph.nodes[n2]['vertex']) - return np.linalg.norm(l1-l2) + return np.linalg.norm(l1 - l2) def _path_search(self, origin, destination): """ @@ -305,7 +306,7 @@ def _successive_last_intersection_edge(self, index, route): last_intersection_edge = None last_node = None - for node1, node2 in [(route[i], route[i+1]) for i in range(index, len(route)-1)]: + for node1, node2 in [(route[i], route[i + 1]) for i in range(index, len(route) - 1)]: candidate_edge = self._graph.edges[node1, node2] if node1 == route[index]: last_intersection_edge = candidate_edge @@ -324,9 +325,9 @@ def _turn_decision(self, index, route, threshold=math.radians(35)): """ decision = None - previous_node = route[index-1] + previous_node = route[index - 1] current_node = route[index] - next_node = route[index+1] + next_node = route[index + 1] next_edge = self._graph.edges[current_node, next_node] if index > 0: if self._previous_decision != RoadOption.VOID \ @@ -352,12 +353,12 @@ def _turn_decision(self, index, route, threshold=math.radians(35)): for neighbor in self._graph.successors(current_node): select_edge = self._graph.edges[current_node, neighbor] if select_edge['type'] == RoadOption.LANEFOLLOW: - if neighbor != route[index+1]: + if neighbor != route[index + 1]: sv = select_edge['net_vector'] cross_list.append(np.cross(cv, sv)[2]) next_cross = np.cross(cv, nv)[2] deviation = math.acos(np.clip( - np.dot(cv, nv)/(np.linalg.norm(cv)*np.linalg.norm(nv)), -1.0, 1.0)) + np.dot(cv, nv) / (np.linalg.norm(cv) * np.linalg.norm(nv)), -1.0, 1.0)) if not cross_list: cross_list.append(0) if deviation < threshold: diff --git a/srunner/tests/carla_mocks/agents/navigation/local_planner.py b/srunner/tests/carla_mocks/agents/navigation/local_planner.py index 82f8c3f1d..46549e760 100644 --- a/srunner/tests/carla_mocks/agents/navigation/local_planner.py +++ b/srunner/tests/carla_mocks/agents/navigation/local_planner.py @@ -223,7 +223,7 @@ def run_step(self, debug=False): # Purge the queue of obsolete waypoints veh_location = self._vehicle.get_location() vehicle_speed = get_speed(self._vehicle) / 3.6 - self._min_distance = self._base_min_distance + 0.5 *vehicle_speed + self._min_distance = self._base_min_distance + 0.5 * vehicle_speed num_waypoint_removed = 0 for waypoint, _ in self._waypoints_queue: diff --git a/srunner/tests/carla_mocks/agents/tools/misc.py b/srunner/tests/carla_mocks/agents/tools/misc.py index 2d3d4c334..ba45cb03c 100644 --- a/srunner/tests/carla_mocks/agents/tools/misc.py +++ b/srunner/tests/carla_mocks/agents/tools/misc.py @@ -12,6 +12,7 @@ import numpy as np import carla + def draw_waypoints(world, waypoints, z=0.5): """ Draw a list of waypoints at a certain height given in z. @@ -39,6 +40,7 @@ def get_speed(vehicle): return 3.6 * math.sqrt(vel.x ** 2 + vel.y ** 2 + vel.z ** 2) + def get_trafficlight_trigger_location(traffic_light): """ Calculates the yaw of the waypoint that represents the trigger volume of the traffic light diff --git a/srunner/tests/carla_mocks/carla.py b/srunner/tests/carla_mocks/carla.py index e5c66b525..076d66266 100644 --- a/srunner/tests/carla_mocks/carla.py +++ b/srunner/tests/carla_mocks/carla.py @@ -133,6 +133,9 @@ class Waypoint(): class Map: name = "" + def __init__(self, name='Town01'): + self.name = name + def get_spawn_points(self): return [] @@ -172,6 +175,24 @@ class WeatherParameters: mie_scattering_scale = 0.000000 rayleigh_scattering_scale = 0.033100 + def __init__(self, cloudiness=0.000000, precipitation=0.000000, precipitation_deposits=0.000000, + wind_intensity=0.000000, sun_azimuth_angle=0.000000, sun_altitude_angle=0.000000, + fog_density=0.000000, fog_distance=0.000000, fog_falloff=0.000000, wetness=0.000000, + scattering_intensity=0.000000, mie_scattering_scale=0.000000, rayleigh_scattering_scale=0.033100): + self.cloudiness = cloudiness + self.precipitation = precipitation + self.precipitation_deposits = precipitation_deposits + self.wind_intensity = wind_intensity + self.sun_azimuth_angle = sun_azimuth_angle + self.sun_altitude_angle = sun_altitude_angle + self.fog_density = fog_density + self.fog_distance = fog_distance + self.fog_falloff = fog_falloff + self.wetness = wetness + self.scattering_intensity = scattering_intensity + self.mie_scattering_scale = mie_scattering_scale + self.rayleigh_scattering_scale = rayleigh_scattering_scale + class WorldSettings: synchronous_mode = False @@ -245,12 +266,16 @@ class Vehicle(Actor): class World: actors = [] + map = Map() def get_settings(self): return WorldSettings() def get_map(self): - return Map() + return self.map + + def set_map(self, map): + self.map = map def get_blueprint_library(self): return CarlaBluePrintLibrary() @@ -282,6 +307,7 @@ class Client: world = World() def load_world(self, name): + self.world.set_map(Map(name)) return None def get_world(self): @@ -307,6 +333,7 @@ def __init__(self, id): return reponse_list + class AttachmentType: Rigid = 0 SpringArm = 1 diff --git a/srunner/tools/background_manager.py b/srunner/tools/background_manager.py index 436ff4262..cf1433681 100644 --- a/srunner/tools/background_manager.py +++ b/srunner/tools/background_manager.py @@ -134,6 +134,7 @@ class StopBackVehicles(AtomicBehavior): Updates the blackboard to tell the background activity to stop the vehicles behind the ego as to not interfere with the scenarios. This only works at roads, not junctions. """ + def __init__(self, name="StopBackVehicles"): super().__init__(name) @@ -147,6 +148,7 @@ class StartBackVehicles(AtomicBehavior): """ Updates the blackboard to tell the background activity to restart the vehicles behind the ego. """ + def __init__(self, name="StartBackVehicles"): super().__init__(name) @@ -161,6 +163,7 @@ class LeaveSpaceInFront(AtomicBehavior): Updates the blackboard to tell the background activity that the ego needs more space in front. This only works at roads, not junctions. """ + def __init__(self, space, name="LeaveSpaceInFront"): self._space = space super().__init__(name) @@ -175,6 +178,7 @@ class SwitchRouteSources(AtomicBehavior): """ Updates the blackboard to tell the background activity to (de)activate all route sources """ + def __init__(self, enabled=True, name="SwitchRouteSources"): self._enabled = enabled super().__init__(name) @@ -194,6 +198,7 @@ class RemoveRoadLane(AtomicBehavior): lane_wp (carla.Waypoint): A carla.Waypoint active (bool) """ + def __init__(self, lane_wp, name="RemoveRoadLane"): self._lane_wp = lane_wp super().__init__(name) @@ -212,6 +217,7 @@ class ReAddRoadLane(AtomicBehavior): offset: 0 to readd the ego lane, 1 for the right side lane, -1 for the left... active (bool) """ + def __init__(self, offset, name="BA_ReAddRoadLane"): self._offset = offset super().__init__(name) @@ -227,6 +233,7 @@ class LeaveSpaceInFront(AtomicBehavior): Updates the blackboard to tell the background activity that the ego needs more space in front. This only works at roads, not junctions. """ + def __init__(self, space, name="LeaveSpaceInFront"): self._space = space super().__init__(name) @@ -242,6 +249,7 @@ class LeaveCrossingSpace(AtomicBehavior): Updates the blackboard to tell the background activity that the ego needs more space in front. This only works at roads, not junctions. """ + def __init__(self, collision_wp, name="LeaveCrossingSpace"): self._collision_wp = collision_wp super().__init__(name) @@ -251,6 +259,7 @@ def update(self): py_trees.blackboard.Blackboard().set("BA_LeaveCrossingSpace", self._collision_wp, overwrite=True) return py_trees.common.Status.SUCCESS + class HandleJunctionScenario(AtomicBehavior): """ Updates the blackboard to tell the background activity to adapt to a junction scenario @@ -265,6 +274,7 @@ class HandleJunctionScenario(AtomicBehavior): It also deactivates the road sources. active (bool) """ + def __init__(self, clear_junction=True, clear_ego_entry=True, remove_entries=[], remove_exits=[], stop_entries=True, extend_road_exit=0, name="HandleJunctionScenario"): diff --git a/srunner/tools/openscenario_parser.py b/srunner/tools/openscenario_parser.py index a32b5d6ea..05181f7d8 100644 --- a/srunner/tools/openscenario_parser.py +++ b/srunner/tools/openscenario_parser.py @@ -274,7 +274,7 @@ def get_traffic_light_from_osc_name(name): elif name.startswith("pos="): tl_pos = name[4:] pos = tl_pos.split(",") - for carla_tl in CCarlaDataProvider.get_all_actors().filter('traffic.traffic_light'): + for carla_tl in CarlaDataProvider.get_all_actors().filter('traffic.traffic_light'): carla_tl_location = carla_tl.get_transform().location distance = carla_tl_location.distance(carla.Location(float(pos[0]), float(pos[1]), @@ -815,7 +815,7 @@ def convert_position_to_transform(position, actor_list=None): if not OpenScenarioParser.use_carla_coordinate_system: # multiply -1 because unlike offset t road is -ve for right side - t = -1*t + t = -1 * t transform = get_offset_transform(transform, t) return transform @@ -1278,7 +1278,8 @@ def convert_maneuver_to_atomic(action, actor, actor_list, catalogs, config): atomic = ActorDestroy(entity_ref_actor) elif entity_action.find('AddEntityAction') is not None: position = entity_action.find('AddEntityAction').find("Position") - actor_transform = OpenScenarioParser.convert_position_to_transform(position) + actor_transform = OpenScenarioParser.convert_position_to_transform( + position, config.other_actors + config.ego_vehicles) entity_ref_actor = None for _actor in config.other_actors: if _actor.rolename == entity_ref: diff --git a/srunner/tools/route_manipulation.py b/srunner/tools/route_manipulation.py index c657c1b0f..6eec685d3 100644 --- a/srunner/tools/route_manipulation.py +++ b/srunner/tools/route_manipulation.py @@ -134,7 +134,7 @@ def interpolate_trajectory(waypoints_trajectory, hop_resolution=1.0): """ Given some raw keypoints interpolate a full dense trajectory to be used by the user. returns the full interpolated route both in GPS coordinates and also in its original form. - + Args: - waypoints_trajectory: the current coarse trajectory - hop_resolution: distance between the trajectory's waypoints diff --git a/srunner/tools/scenario_helper.py b/srunner/tools/scenario_helper.py index 4aa03b641..bb492dda2 100644 --- a/srunner/tools/scenario_helper.py +++ b/srunner/tools/scenario_helper.py @@ -185,7 +185,7 @@ def get_geometric_linear_intersection(ego_location, other_location, move_to_junc if z == 0: return None - return carla.Location(x=x/z, y=y/z, z=0) + return carla.Location(x=x / z, y=y / z, z=0) def get_location_in_distance(actor, distance): @@ -677,10 +677,10 @@ def get_troad_from_transform(actor_transform): if not right_lanes or not left_lanes: closest_road_edge = min(distance_from_lm_lane_edge, distance_from_rm_lane_edge) if closest_road_edge == distance_from_lm_lane_edge: - t_road = -1*t_road + t_road = -1 * t_road else: if c_wp.lane_id < 0: - t_road = -1*t_road + t_road = -1 * t_road return t_road diff --git a/tests/run_testcase/run_ast_testcases.py b/tests/run_testcase/run_ast_testcases.py index 74d129e6e..ef221f110 100644 --- a/tests/run_testcase/run_ast_testcases.py +++ b/tests/run_testcase/run_ast_testcases.py @@ -1,3 +1,5 @@ +from tests.run_testcase.log_msg import create_LogMsg as log_msg +from tests.run_testcase.test_base import TestASTClass import unittest import os import sys @@ -10,8 +12,6 @@ # Add the current working directory to the module search path sys.path.append(os.getcwd()) -from tests.run_testcase.test_base import TestASTClass -from tests.run_testcase.log_msg import create_LogMsg as log_msg log_msg.is_open = True # modify current working directory diff --git a/tests/run_testcase/run_symbol_testcases.py b/tests/run_testcase/run_symbol_testcases.py index 30927a9e6..d2ec42624 100644 --- a/tests/run_testcase/run_symbol_testcases.py +++ b/tests/run_testcase/run_symbol_testcases.py @@ -1,3 +1,5 @@ +from tests.run_testcase.log_msg import create_LogMsg as log_msg +from tests.run_testcase.test_base import TestSymbolClass import unittest import os import sys @@ -10,8 +12,6 @@ # Add the current working directory to the module search path sys.path.append(os.getcwd()) -from tests.run_testcase.test_base import TestSymbolClass -from tests.run_testcase.log_msg import create_LogMsg as log_msg log_msg.is_open = True # modify current working directory diff --git a/tests/test-ast-listener.py b/tests/test-ast-listener.py index f55bfc9c1..3c21a73ad 100644 --- a/tests/test-ast-listener.py +++ b/tests/test-ast-listener.py @@ -29,6 +29,8 @@ # nodes:number the nodes in traversal order and line them with numbers # pindex:id of the parent node # g:graphviz + + def render_ast(node, nodes, pindex, g): if not isinstance(node, Tuple): name = str(node) @@ -44,65 +46,67 @@ def render_ast(node, nodes, pindex, g): for i in range(0, node.get_child_count()): render_ast(node.get_child(i), nodes, index, g) + class InvocationTest(ASTListener): def __init__(self): self.arguments = [] self.__value = None - def enter_modifier_invocation(self, node: ast_node.ModifierInvocation): - #print("enter modifier invocation!") + def enter_modifier_invocation(self, node: ast_node.ModifierInvocation): + # print("enter modifier invocation!") # print("modifier name:", node.modifier_name) self.arguments = [] self.__value = None - def exit_modifier_invocation(self, node: ast_node.ModifierInvocation): - #print("exit modifier invocation!") - #print(self.arguments) + def exit_modifier_invocation(self, node: ast_node.ModifierInvocation): + # print("exit modifier invocation!") + # print(self.arguments) pass - def enter_named_argument(self, node: ast_node.NamedArgument): + def enter_named_argument(self, node: ast_node.NamedArgument): self.__value = None - def exit_named_argument(self, node: ast_node.NamedArgument): + def exit_named_argument(self, node: ast_node.NamedArgument): self.arguments.append((node.argument_name, self.__value)) - def enter_physical_literal(self, node: ast_node.PhysicalLiteral): + def enter_physical_literal(self, node: ast_node.PhysicalLiteral): self.arguments.append((node.value, node.unit_name)) - def exit_physical_literal(self, node: ast_node.PhysicalLiteral): + def exit_physical_literal(self, node: ast_node.PhysicalLiteral): pass - def enter_integer_literal(self, node: ast_node.IntegerLiteral): + def enter_integer_literal(self, node: ast_node.IntegerLiteral): self.__value = node.value - def exit_integer_literal(self, node: ast_node.IntegerLiteral): + def exit_integer_literal(self, node: ast_node.IntegerLiteral): pass - def enter_float_literal(self, node: ast_node.FloatLiteral): + def enter_float_literal(self, node: ast_node.FloatLiteral): self.__value = node.value - def exit_float_literal(self, node: ast_node.FloatLiteral): + def exit_float_literal(self, node: ast_node.FloatLiteral): pass - def enter_bool_literal(self, node: ast_node.BoolLiteral): + def enter_bool_literal(self, node: ast_node.BoolLiteral): self.__value = node.value - def exit_bool_literal(self, node: ast_node.BoolLiteral): + def exit_bool_literal(self, node: ast_node.BoolLiteral): pass - def enter_string_literal(self, node: ast_node.StringLiteral): + def enter_string_literal(self, node: ast_node.StringLiteral): self.__value = node.value - def exit_string_literal(self, node: ast_node.StringLiteral): + def exit_string_literal(self, node: ast_node.StringLiteral): pass - def enter_identifier(self, node: ast_node.Identifier): + def enter_identifier(self, node: ast_node.Identifier): self.__value = node.name - def exit_identifier(self, node: ast_node.Identifier): + def exit_identifier(self, node: ast_node.Identifier): pass - + + def main(input_stream): quiet = False OscErrorListeners = OscErrorListener(input_stream) @@ -124,22 +128,20 @@ def main(input_stream): ast = build_ast.get_ast() symbol = build_ast.get_symbol() - graph = graphviz.Graph(node_attr={'shape': 'plaintext'},format='png') - #render_symbol(symbol, [], 0, graph) - #render_ast(ast, [], 0, graph) - #graph.view() + graph = graphviz.Graph(node_attr={'shape': 'plaintext'}, format='png') + # render_symbol(symbol, [], 0, graph) + # render_ast(ast, [], 0, graph) + # graph.view() invocation_walker = ASTWalker() invocation_listener = InvocationTest() invocation_walker.walk(invocation_listener, ast) - - if not quiet: - LOG_INFO("Errors: "+ str(errors)) - #print_parse_tree(tree, parser.ruleNames) + LOG_INFO("Errors: " + str(errors)) + # print_parse_tree(tree, parser.ruleNames) return errors - + if __name__ == '__main__': error_file_list = [] @@ -149,24 +151,23 @@ def main(input_stream): files.sort() for fi in files: fpath = os.path.join(filepath, fi) - LOG_INFO("======================== "+fi+" ========================") + LOG_INFO("======================== " + fi + " ========================") new_file, import_msg = Preprocess(fpath).import_process() input_stream = FileStream(new_file, encoding='utf-8') - if main(input_stream)>0: + if main(input_stream) > 0: error_file_list.append(fi) import_msg.clear_msg() - LOG_INFO("======================== "+"error file result"+" ========================") + LOG_INFO("======================== " + "error file result" + " ========================") for error_file in error_file_list: - LOG_INFO(error_file) + LOG_INFO(error_file) elif os.path.isfile(sys.argv[1]): new_file, import_msg = Preprocess(sys.argv[1]).import_process() input_stream = FileStream(new_file, encoding='utf-8') - if main(input_stream)>0: - LOG_INFO("======================== "+"error file result"+" ========================") + if main(input_stream) > 0: + LOG_INFO("======================== " + "error file result" + " ========================") LOG_INFO(sys.argv[1]) pass else: pass - diff --git a/tests/test-ast-visitor.py b/tests/test-ast-visitor.py index 81d06d895..f479db4c0 100644 --- a/tests/test-ast-visitor.py +++ b/tests/test-ast-visitor.py @@ -28,6 +28,8 @@ # nodes:number the nodes in traversal order and line them with numbers # pindex:id of the parent node # g:graphviz + + def render_ast(node, nodes, pindex, g): if not isinstance(node, Tuple): name = str(node) @@ -43,9 +45,12 @@ def render_ast(node, nodes, pindex, g): for i in range(0, node.get_child_count()): render_ast(node.get_child(i), nodes, index, g) + operator = [] num = [] all = [] + + def traverse_list(list_name): for ex in list_name: if isinstance(ex, list): @@ -56,19 +61,16 @@ def traverse_list(list_name): else: num.append(ex) all.append(ex) - - - class InvocationTest(ASTVisitor): - def visit_modifier_invocation(self, node: ast_node.ModifierInvocation): + def visit_modifier_invocation(self, node: ast_node.ModifierInvocation): print("visit modifier invocation!") print("modifier name:", node.modifier_name) arguments = self.visit_children(node) print(arguments) - + def visit_method_body(self, node: ast_node.MethodBody): print("visit method body!") print("method body name:", node.type) @@ -87,7 +89,7 @@ def visit_method_body(self, node: ast_node.MethodBody): right = tempStack.pop() left = tempStack.pop() opnum = tempStack.pop() - expression = opnum + ' ' + ex + ' [' + left + ', '+ right + ']' + expression = opnum + ' ' + ex + ' [' + left + ', ' + right + ']' tempStack.append(expression) else: tempStack.append(ex) @@ -95,37 +97,35 @@ def visit_method_body(self, node: ast_node.MethodBody): operator.clear() num.clear() all.clear() - + def visit_relation_expression(self, node: ast_node.RelationExpression): return [self.visit_children(node), node.operator] def visit_binary_expression(self, node: ast_node.BinaryExpression): return [self.visit_children(node), node.operator] - def visit_named_argument(self, node: ast_node.NamedArgument): + def visit_named_argument(self, node: ast_node.NamedArgument): return node.argument_name, self.visit_children(node) - def visit_physical_literal(self, node: ast_node.PhysicalLiteral): + def visit_physical_literal(self, node: ast_node.PhysicalLiteral): return node.value, node.unit_name - def visit_integer_literal(self, node: ast_node.IntegerLiteral): + def visit_integer_literal(self, node: ast_node.IntegerLiteral): return node.value - def visit_float_literal(self, node: ast_node.FloatLiteral): + def visit_float_literal(self, node: ast_node.FloatLiteral): return node.value - def visit_bool_literal(self, node: ast_node.BoolLiteral): + def visit_bool_literal(self, node: ast_node.BoolLiteral): return node.value - def visit_string_literal(self, node: ast_node.StringLiteral): + def visit_string_literal(self, node: ast_node.StringLiteral): return node.value - def visit_identifier(self, node: ast_node.Identifier): + def visit_identifier(self, node: ast_node.Identifier): return node.name - - def main(input_stream): quiet = False OscErrorListeners = OscErrorListener(input_stream) @@ -146,20 +146,18 @@ def main(input_stream): walker.walk(build_ast, tree) ast = build_ast.get_ast() - #graph = graphviz.Graph(node_attr={'shape': 'plaintext'},format='png') - #render_ast(ast, [], 0, graph) - #graph.view() + # graph = graphviz.Graph(node_attr={'shape': 'plaintext'},format='png') + # render_ast(ast, [], 0, graph) + # graph.view() invocation_visitor = InvocationTest() invocation_visitor.visit(ast) - - if not quiet: - LOG_INFO("Errors: "+ str(errors)) - #print_parse_tree(tree, parser.ruleNames) + LOG_INFO("Errors: " + str(errors)) + # print_parse_tree(tree, parser.ruleNames) return errors - + if __name__ == '__main__': error_file_list = [] @@ -171,24 +169,23 @@ def main(input_stream): files.sort() for fi in files: fpath = os.path.join(filepath, fi) - LOG_INFO("======================== "+fi+" ========================") + LOG_INFO("======================== " + fi + " ========================") new_file, import_msg = Preprocess(fpath).import_process() input_stream = FileStream(new_file, encoding='utf-8') - if main(input_stream)>0: + if main(input_stream) > 0: error_file_list.append(fi) import_msg.clear_msg() - LOG_INFO("======================== "+"error file result"+" ========================") + LOG_INFO("======================== " + "error file result" + " ========================") for error_file in error_file_list: - LOG_INFO(error_file) + LOG_INFO(error_file) elif os.path.isfile(sys.argv[1]): new_file, import_msg = Preprocess(sys.argv[1]).import_process() input_stream = FileStream(new_file, encoding='utf-8') - if main(input_stream)>0: - LOG_INFO("======================== "+"error file result"+" ========================") + if main(input_stream) > 0: + LOG_INFO("======================== " + "error file result" + " ========================") LOG_INFO(sys.argv[1]) pass else: pass - diff --git a/tests/test-ast.py b/tests/test-ast.py index c4cbe220a..82ef07f60 100644 --- a/tests/test-ast.py +++ b/tests/test-ast.py @@ -1,3 +1,13 @@ +import graphviz +from srunner.osc2.ast_manager.ast_builder import ASTBuilder +from srunner.osc2.osc2_parser.OpenSCENARIO2Parser import OpenSCENARIO2Parser +from srunner.osc2.osc2_parser.OpenSCENARIO2Lexer import OpenSCENARIO2Lexer +from srunner.osc2.error_manager.error_listener import OscErrorListener +from srunner.osc2.utils.tools import * +from srunner.osc2.utils.log_manager import * +import srunner.osc2.ast_manager.ast_node as ast_node +from srunner.osc2.ast_manager.ast_node import AST +from srunner.osc2.osc_preprocess.pre_process import ImportFile, Preprocess import os import sys from os.path import abspath, dirname @@ -8,23 +18,13 @@ sys.path.append('../') except IndexError: pass -from srunner.osc2.osc_preprocess.pre_process import ImportFile, Preprocess -from srunner.osc2.ast_manager.ast_node import AST -import srunner.osc2.ast_manager.ast_node as ast_node -from srunner.osc2.utils.log_manager import * -from srunner.osc2.utils.tools import * -from srunner.osc2.error_manager.error_listener import OscErrorListener -from srunner.osc2.osc2_parser.OpenSCENARIO2Lexer import OpenSCENARIO2Lexer -from srunner.osc2.osc2_parser.OpenSCENARIO2Parser import OpenSCENARIO2Parser -from srunner.osc2.ast_manager.ast_builder import ASTBuilder - -import graphviz # node:node of the tree # nodes:number the nodes in traversal order and line them with numbers # pindex:id of the parent node # g:graphviz + def render_ast(node, nodes, pindex, g): if not isinstance(node, Tuple): name = str(node) @@ -39,7 +39,8 @@ def render_ast(node, nodes, pindex, g): if isinstance(node, ast_node.AST): for i in range(0, node.get_child_count()): render_ast(node.get_child(i), nodes, index, g) - + + def main(input_stream, output_name): quiet = False OscErrorListeners = OscErrorListener(input_stream) @@ -62,11 +63,11 @@ def main(input_stream, output_name): graph = graphviz.Graph(node_attr={'shape': 'plaintext'}, format='png') render_ast(ast_listener.ast, [], 0, graph) # graph.view() #generate and view graph - #graph.render(cleanup=True, outfile=output_name.split('\\')[-1]+".png") #generate and save graph, but not view + # graph.render(cleanup=True, outfile=output_name.split('\\')[-1]+".png") #generate and save graph, but not view if not quiet: - LOG_INFO("Errors: "+ str(errors)) - #print_parse_tree(tree, parser.ruleNames) + LOG_INFO("Errors: " + str(errors)) + # print_parse_tree(tree, parser.ruleNames) return errors @@ -80,24 +81,23 @@ def main(input_stream, output_name): files.sort() for fi in files: fpath = os.path.join(filepath, fi) - LOG_INFO("======================== "+fi+" ========================") + LOG_INFO("======================== " + fi + " ========================") new_file, import_msg = Preprocess(fpath).import_process() input_stream = FileStream(new_file, encoding='utf-8') - if main(input_stream, fpath)>0: + if main(input_stream, fpath) > 0: error_file_list.append(fi) import_msg.clear_msg() - LOG_INFO("======================== "+"error file result"+" ========================") + LOG_INFO("======================== " + "error file result" + " ========================") for error_file in error_file_list: - LOG_INFO(error_file) + LOG_INFO(error_file) elif os.path.isfile(sys.argv[1]): new_file, import_msg = Preprocess(sys.argv[1]).import_process() input_stream = FileStream(new_file, encoding='utf-8') if main(input_stream, sys.argv[1]) > 0: - LOG_INFO("======================== "+"error file result"+" ========================") + LOG_INFO("======================== " + "error file result" + " ========================") LOG_INFO(sys.argv[1]) pass else: pass - diff --git a/tests/test-symbol.py b/tests/test-symbol.py index 46684ff20..623735c27 100644 --- a/tests/test-symbol.py +++ b/tests/test-symbol.py @@ -1,3 +1,9 @@ +from srunner.osc2.ast_manager.ast_builder import ASTBuilder +from srunner.osc2.osc2_parser.OpenSCENARIO2Parser import OpenSCENARIO2Parser +from srunner.osc2.osc2_parser.OpenSCENARIO2Lexer import OpenSCENARIO2Lexer +from srunner.osc2.error_manager.error_listener import OscErrorListener +from srunner.osc2.utils.log_manager import * +from srunner.osc2.osc_preprocess.pre_process import Preprocess import os import sys @@ -8,15 +14,7 @@ except IndexError: pass -from srunner.osc2.osc_preprocess.pre_process import Preprocess -from srunner.osc2.utils.log_manager import * -from srunner.osc2.error_manager.error_listener import OscErrorListener -from srunner.osc2.osc2_parser.OpenSCENARIO2Lexer import OpenSCENARIO2Lexer -from srunner.osc2.osc2_parser.OpenSCENARIO2Parser import OpenSCENARIO2Parser -from srunner.osc2.ast_manager.ast_builder import ASTBuilder - - def main(input_stream): quiet = False OscErrorListeners = OscErrorListener(input_stream) @@ -36,10 +34,10 @@ def main(input_stream): walker.walk(ast_listener, tree) if not quiet: - LOG_INFO("Errors: "+ str(errors)) - #print_parse_tree(tree, parser.ruleNames) + LOG_INFO("Errors: " + str(errors)) + # print_parse_tree(tree, parser.ruleNames) return errors - + if __name__ == '__main__': error_file_list = [] @@ -51,23 +49,22 @@ def main(input_stream): files.sort() for fi in files: fpath = os.path.join(filepath, fi) - LOG_INFO("======================== "+fi+" ========================") + LOG_INFO("======================== " + fi + " ========================") new_file, import_msg = Preprocess(fpath).import_process() input_stream = FileStream(fpath, encoding='utf-8') - if main(input_stream)>0: + if main(input_stream) > 0: error_file_list.append(fi) import_msg.clear_msg() - LOG_INFO("======================== "+"error file result"+" ========================") + LOG_INFO("======================== " + "error file result" + " ========================") for error_file in error_file_list: - LOG_INFO(error_file) + LOG_INFO(error_file) elif os.path.isfile(sys.argv[1]): new_file, import_msg = Preprocess(sys.argv[1]).import_process() input_stream = FileStream(sys.argv[1], encoding='utf-8') - if main(input_stream)>0: - LOG_INFO("======================== "+"error file result"+" ========================") + if main(input_stream) > 0: + LOG_INFO("======================== " + "error file result" + " ========================") LOG_INFO(sys.argv[1]) pass else: pass -