diff --git a/manual_control.py b/manual_control.py index 9a8e6237c..8e8ffa7e6 100755 --- a/manual_control.py +++ b/manual_control.py @@ -396,6 +396,7 @@ def on_world_tick(self, timestamp): self.simulation_time = timestamp.elapsed_seconds def tick(self, world, clock): + # type: (carla.World, pygame.time.Clock) -> None self._notifications.tick(world, clock) if not self._show_info: return @@ -781,10 +782,12 @@ 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=-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=-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 diff --git a/metrics_manager.py b/metrics_manager.py index 3cdea4c4b..77f1d3255 100644 --- a/metrics_manager.py +++ b/metrics_manager.py @@ -130,7 +130,8 @@ 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" + # pylint: enable=line-too-long parser = argparse.ArgumentParser(description=description, formatter_class=RawTextHelpFormatter) @@ -138,13 +139,23 @@ def main(): help='IP of the host server (default: localhost)') parser.add_argument('--port', '-p', default=2000, help='TCP port to listen to (default: 2000)') - parser.add_argument('--log', required=True, - help='Path to the CARLA recorder .log file (relative to SCENARIO_RUNNER_ROOT).\nThis file is created by the record functionality at ScenarioRunner') - parser.add_argument('--metric', required=True, - help='Path to the .py file defining the used metric.\nSome examples at srunner/metrics') - parser.add_argument('--criteria', default="", - help='Path to the .json file with the criteria information.\nThis file is created by the record functionality at ScenarioRunner') - # pylint: enable=line-too-long + parser.add_argument( + "--log", + required=True, + help="Path to the CARLA recorder .log file (relative to SCENARIO_RUNNER_ROOT)." + "\nThis file is created by the record functionality at ScenarioRunner", + ) + parser.add_argument( + "--metric", + required=True, + help="Path to the .py file defining the used metric.\nSome examples at srunner/metrics", + ) + parser.add_argument( + "--criteria", + default="", + help="Path to the .json file with the criteria information." + "\nThis file is created by the record functionality at ScenarioRunner", + ) args = parser.parse_args() diff --git a/no_rendering_mode.py b/no_rendering_mode.py index ec24d1dab..48b22a1dc 100755 --- a/no_rendering_mode.py +++ b/no_rendering_mode.py @@ -490,22 +490,55 @@ def draw_broken_line(surface, color, closed, points, width): def get_lane_markings(lane_marking_type, lane_marking_color, waypoints, sign): margin = 0.20 - if lane_marking_type == carla.LaneMarkingType.Broken or (lane_marking_type == carla.LaneMarkingType.Solid): - marking_1 = [world_to_pixel(lateral_shift(w.transform, sign * w.lane_width * 0.5)) for w in waypoints] + if lane_marking_type == carla.LaneMarkingType.Broken or ( + lane_marking_type == carla.LaneMarkingType.Solid + ): + marking_1 = [ + world_to_pixel( + lateral_shift(w.transform, sign * w.lane_width * 0.5) + ) + for w in waypoints + ] return [(lane_marking_type, lane_marking_color, marking_1)] - elif lane_marking_type == carla.LaneMarkingType.SolidBroken or lane_marking_type == carla.LaneMarkingType.BrokenSolid: - marking_1 = [world_to_pixel(lateral_shift(w.transform, sign * w.lane_width * 0.5)) for w in waypoints] - marking_2 = [world_to_pixel(lateral_shift(w.transform, - sign * (w.lane_width * 0.5 + margin * 2))) for w in waypoints] - return [(carla.LaneMarkingType.Solid, lane_marking_color, marking_1), - (carla.LaneMarkingType.Broken, lane_marking_color, marking_2)] + elif ( + lane_marking_type == carla.LaneMarkingType.SolidBroken + or lane_marking_type == carla.LaneMarkingType.BrokenSolid + ): + marking_1 = [ + world_to_pixel( + lateral_shift(w.transform, sign * w.lane_width * 0.5) + ) + for w in waypoints + ] + marking_2 = [ + world_to_pixel( + lateral_shift( + w.transform, sign * (w.lane_width * 0.5 + margin * 2) + ) + ) + for w in waypoints + ] + return [ + (carla.LaneMarkingType.Solid, lane_marking_color, marking_1), + (carla.LaneMarkingType.Broken, lane_marking_color, marking_2), + ] elif lane_marking_type == carla.LaneMarkingType.BrokenBroken: - marking = [world_to_pixel(lateral_shift(w.transform, - sign * (w.lane_width * 0.5 - margin))) for w in waypoints] + marking = [ + world_to_pixel( + lateral_shift(w.transform, sign * (w.lane_width * 0.5 - margin)) + ) + for w in waypoints + ] return [(carla.LaneMarkingType.Broken, lane_marking_color, marking)] elif lane_marking_type == carla.LaneMarkingType.SolidSolid: - marking = [world_to_pixel(lateral_shift(w.transform, - sign * ((w.lane_width * 0.5) - margin))) for w in waypoints] + marking = [ + world_to_pixel( + lateral_shift( + w.transform, sign * ((w.lane_width * 0.5) - margin) + ) + ) + for w in waypoints + ] return [(carla.LaneMarkingType.Solid, lane_marking_color, marking)] return [(carla.LaneMarkingType.NONE, carla.LaneMarkingColor.Other, [])] diff --git a/scenario_runner.py b/scenario_runner.py index f3206e2b7..f06725b9e 100755 --- a/scenario_runner.py +++ b/scenario_runner.py @@ -106,7 +106,11 @@ 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) @@ -582,8 +586,11 @@ def main(): help='Frame rate (Hz) to use in \'sync\' mode (default: 20)') parser.add_argument( - '--scenario', help='Name of the scenario to be executed. Use the preposition \'group:\' to run all scenarios of one class, e.g. ControlLoss or FollowLeadingVehicle') - parser.add_argument('--openscenario', help='Provide an OpenSCENARIO definition') + "--scenario", + help="Name of the scenario to be executed. Use the preposition 'group:' to run all scenarios of one class" + " e.g. ControlLoss or FollowLeadingVehicle", + ) + parser.add_argument("--openscenario", help="Provide an OpenSCENARIO definition") parser.add_argument('--openscenarioparams', help='Overwrited for OpenSCENARIO ParameterDeclaration') parser.add_argument('--openscenario2', help='Provide an openscenario2 definition') parser.add_argument('--route', help='Run a route as a scenario', type=str) @@ -604,11 +611,20 @@ def main(): parser.add_argument('--debug', action="store_true", help='Run with debug output') parser.add_argument('--reloadWorld', action="store_true", help='Reload the CARLA world before starting a scenario (default=True)') - parser.add_argument('--record', type=str, default='', - help='Path were the files will be saved, relative to SCENARIO_RUNNER_ROOT.\nActivates the CARLA recording feature and saves to file all the criteria information.') - parser.add_argument('--randomize', action="store_true", help='Scenario parameters are randomized') - parser.add_argument('--repetitions', default=1, type=int, help='Number of scenario executions') - parser.add_argument('--waitForEgo', action="store_true", help='Connect the scenario to an existing ego vehicle') + parser.add_argument( + "--record", + type=str, + default="", + help="Path were the files will be saved, relative to SCENARIO_RUNNER_ROOT." + "\nActivates the CARLA recording feature and saves to file all the criteria information.", + ) + parser.add_argument("--randomize", action="store_true", help="Scenario parameters are randomized") + parser.add_argument("--repetitions", default=1, type=int, help="Number of scenario executions") + parser.add_argument( + "--waitForEgo", + action="store_true", + help="Connect the scenario to an existing ego vehicle", + ) arguments = parser.parse_args() # pylint: enable=line-too-long diff --git a/srunner/autoagents/ros_agent.py b/srunner/autoagents/ros_agent.py index deb537d4e..b2690a4bc 100644 --- a/srunner/autoagents/ros_agent.py +++ b/srunner/autoagents/ros_agent.py @@ -30,9 +30,13 @@ from sensor_msgs.point_cloud2 import create_cloud_xyz32 from std_msgs.msg import Header, String import tf -# pylint: disable=line-too-long -from carla_msgs.msg import CarlaEgoVehicleStatus, CarlaEgoVehicleInfo, CarlaEgoVehicleInfoWheel, CarlaEgoVehicleControl, CarlaWorldInfo -# pylint: enable=line-too-long +from carla_msgs.msg import ( + CarlaEgoVehicleStatus, + CarlaEgoVehicleInfo, + CarlaEgoVehicleInfoWheel, + CarlaEgoVehicleControl, + CarlaWorldInfo, +) from srunner.autoagents.autonomous_agent import AutonomousAgent @@ -122,42 +126,73 @@ def setup(self, path_to_conf_file): self.cv_bridge = CvBridge() # setup ros publishers for sensors - # pylint: disable=line-too-long for sensor in self.sensors(): - self.id_to_sensor_type_map[sensor['id']] = sensor['type'] - if sensor['type'] == 'sensor.camera.rgb': - self.publisher_map[sensor['id']] = rospy.Publisher( - '/carla/ego_vehicle/camera/rgb/' + sensor['id'] + "/image_color", Image, queue_size=1, latch=True) - self.id_to_camera_info_map[sensor['id']] = self.build_camera_info(sensor) - self.publisher_map[sensor['id'] + '_info'] = rospy.Publisher( - '/carla/ego_vehicle/camera/rgb/' + sensor['id'] + "/camera_info", CameraInfo, queue_size=1, latch=True) - elif sensor['type'] == 'sensor.lidar.ray_cast': - self.publisher_map[sensor['id']] = rospy.Publisher( - '/carla/ego_vehicle/lidar/' + sensor['id'] + "/point_cloud", PointCloud2, queue_size=1, latch=True) - elif sensor['type'] == 'sensor.other.gnss': - self.publisher_map[sensor['id']] = rospy.Publisher( - '/carla/ego_vehicle/gnss/' + sensor['id'] + "/fix", NavSatFix, queue_size=1, latch=True) - elif sensor['type'] == 'sensor.can_bus': + self.id_to_sensor_type_map[sensor["id"]] = sensor["type"] + if sensor["type"] == "sensor.camera.rgb": + self.publisher_map[sensor["id"]] = rospy.Publisher( + "/carla/ego_vehicle/camera/rgb/" + sensor["id"] + "/image_color", + Image, + queue_size=1, + latch=True, + ) + self.id_to_camera_info_map[sensor["id"]] = self.build_camera_info( + sensor + ) + self.publisher_map[sensor["id"] + "_info"] = rospy.Publisher( + "/carla/ego_vehicle/camera/rgb/" + sensor["id"] + "/camera_info", + CameraInfo, + queue_size=1, + latch=True, + ) + elif sensor["type"] == "sensor.lidar.ray_cast": + self.publisher_map[sensor["id"]] = rospy.Publisher( + "/carla/ego_vehicle/lidar/" + sensor["id"] + "/point_cloud", + PointCloud2, + queue_size=1, + latch=True, + ) + elif sensor["type"] == "sensor.other.gnss": + self.publisher_map[sensor["id"]] = rospy.Publisher( + "/carla/ego_vehicle/gnss/" + sensor["id"] + "/fix", + NavSatFix, + queue_size=1, + latch=True, + ) + elif sensor["type"] == "sensor.can_bus": if not self.vehicle_info_publisher: self.vehicle_info_publisher = rospy.Publisher( - '/carla/ego_vehicle/vehicle_info', CarlaEgoVehicleInfo, queue_size=1, latch=True) + "/carla/ego_vehicle/vehicle_info", + CarlaEgoVehicleInfo, + queue_size=1, + latch=True, + ) if not self.vehicle_status_publisher: self.vehicle_status_publisher = rospy.Publisher( - '/carla/ego_vehicle/vehicle_status', CarlaEgoVehicleStatus, queue_size=1, latch=True) - elif sensor['type'] == 'sensor.hd_map': + "/carla/ego_vehicle/vehicle_status", + CarlaEgoVehicleStatus, + queue_size=1, + latch=True, + ) + elif sensor["type"] == "sensor.hd_map": if not self.odometry_publisher: self.odometry_publisher = rospy.Publisher( - '/carla/ego_vehicle/odometry', Odometry, queue_size=1, latch=True) + "/carla/ego_vehicle/odometry", + Odometry, + queue_size=1, + latch=True, + ) if not self.world_info_publisher: self.world_info_publisher = rospy.Publisher( - '/carla/world_info', CarlaWorldInfo, queue_size=1, latch=True) + "/carla/world_info", CarlaWorldInfo, queue_size=1, latch=True + ) if not self.map_file_publisher: - self.map_file_publisher = rospy.Publisher('/carla/map_file', String, queue_size=1, latch=True) + self.map_file_publisher = rospy.Publisher( + "/carla/map_file", String, queue_size=1, latch=True + ) if not self.tf_broadcaster: self.tf_broadcaster = tf.TransformBroadcaster() else: - raise TypeError("Invalid sensor type: {}".format(sensor['type'])) - # pylint: enable=line-too-long + raise TypeError("Invalid sensor type: {}".format(sensor["type"])) def destroy(self): """ @@ -293,9 +328,12 @@ def publish_gnss(self, sensor_id, data): msg.longitude = data[1] msg.altitude = data[2] msg.status.status = NavSatStatus.STATUS_SBAS_FIX - # pylint: disable=line-too-long - msg.status.service = NavSatStatus.SERVICE_GPS | NavSatStatus.SERVICE_GLONASS | NavSatStatus.SERVICE_COMPASS | NavSatStatus.SERVICE_GALILEO - # pylint: enable=line-too-long + msg.status.service = ( + NavSatStatus.SERVICE_GPS + | NavSatStatus.SERVICE_GLONASS + | NavSatStatus.SERVICE_COMPASS + | NavSatStatus.SERVICE_GALILEO + ) self.publisher_map[sensor_id].publish(msg) def publish_camera(self, sensor_id, data): diff --git a/srunner/metrics/tools/metrics_log.py b/srunner/metrics/tools/metrics_log.py index 4dce1e532..449cc0966 100644 --- a/srunner/metrics/tools/metrics_log.py +++ b/srunner/metrics/tools/metrics_log.py @@ -407,10 +407,7 @@ def is_vehicle_light_active(self, light, vehicle_id, frame): """ lights = self.get_vehicle_lights(vehicle_id, frame) - if light in lights: - return True - - return False + return light in lights # Scene lights def get_scene_light_state(self, light_id, frame): diff --git a/srunner/metrics/tools/metrics_parser.py b/srunner/metrics/tools/metrics_parser.py index e7ea1a9e0..d270143e5 100644 --- a/srunner/metrics/tools/metrics_parser.py +++ b/srunner/metrics/tools/metrics_parser.py @@ -507,7 +507,7 @@ def parse_recorder_info(self): elif name == "use_gear_auto_box": name = "use_gear_autobox" - value = True if elements[1] == "true" else False + value = elements[1] == "true" setattr(physics_control, name, value) elif "forward_gears" in name or "wheels" in name: diff --git a/srunner/metrics/tools/osc2_log.py b/srunner/metrics/tools/osc2_log.py index d89e292e2..1880d8d54 100644 --- a/srunner/metrics/tools/osc2_log.py +++ b/srunner/metrics/tools/osc2_log.py @@ -427,10 +427,7 @@ def is_vehicle_light_active(self, light, vehicle_id, frame): """ lights = self.get_vehicle_lights(vehicle_id, frame) - if light in lights: - return True - - return False + return light in lights # Scene lights def get_scene_light_state(self, light_id, frame): diff --git a/srunner/metrics/tools/osc2_trace_parser.py b/srunner/metrics/tools/osc2_trace_parser.py index 8e263c15f..1fdf4b5ad 100644 --- a/srunner/metrics/tools/osc2_trace_parser.py +++ b/srunner/metrics/tools/osc2_trace_parser.py @@ -512,7 +512,7 @@ def parse_recorder_info(self): elif name == "use_gear_auto_box": name = "use_gear_autobox" - value = True if elements[1] == "true" else False + value = elements[1] == "true" setattr(physics_control, name, value) elif "forward_gears" in name or "wheels" in name: diff --git a/srunner/osc2/ast_manager/ast_builder.py b/srunner/osc2/ast_manager/ast_builder.py index f2a24bbfd..2b7d61391 100644 --- a/srunner/osc2/ast_manager/ast_builder.py +++ b/srunner/osc2/ast_manager/ast_builder.py @@ -1648,12 +1648,6 @@ def enterBehaviorInvocation( # Find the scope of type_name scope = self.__current_scope.resolve(name) - if scope: - pass - else: - msg = "behavior name: " + name + " is not defined!" - pass - node = ast_node.BehaviorInvocation(actor, behavior_name) node.set_loc(ctx.start.line, ctx.start.column) node.set_scope(scope) @@ -2083,7 +2077,7 @@ def exitConjunction(self, ctx: OpenSCENARIO2Parser.ConjunctionContext): # Enter a parse tree produced by OpenSCENARIO2Parser#inversion. def enterInversion(self, ctx: OpenSCENARIO2Parser.InversionContext): self.__node_stack.append(self.__cur_node) - if ctx.relation() == None: + if ctx.relation() is None: operator = "not" node = ast_node.LogicalExpression(operator) node.set_loc(ctx.start.line, ctx.start.column) diff --git a/srunner/osc2/ast_manager/ast_listener.py b/srunner/osc2/ast_manager/ast_listener.py index 040798173..bb11d1217 100644 --- a/srunner/osc2/ast_manager/ast_listener.py +++ b/srunner/osc2/ast_manager/ast_listener.py @@ -211,12 +211,6 @@ def enter_positional_argument(self, node: ast_node.PositionalArgument): def exit_positional_argument(self, node: ast_node.PositionalArgument): pass - def enter_variable_declaration(self, node: ast_node.VariableDeclaration): - pass - - def exit_variable_declaration(self, node: ast_node.VariableDeclaration): - pass - def enter_keep_constraint_declaration( self, node: ast_node.KeepConstraintDeclaration ): diff --git a/srunner/osc2/ast_manager/ast_node.py b/srunner/osc2/ast_manager/ast_node.py index 75b97dd6f..3879f6407 100644 --- a/srunner/osc2/ast_manager/ast_node.py +++ b/srunner/osc2/ast_manager/ast_node.py @@ -552,6 +552,10 @@ def accept(self, visitor): class VariableDeclaration(Declaration): + """ + 'var' fieldName (',' fieldName)* ':' typeDeclarator ('=' (sampleExpression | valueExp) )? NEWLINE; + """ + def __init__(self, field_name, field_type): super().__init__() self.field_name = field_name @@ -823,31 +827,6 @@ def accept(self, visitor): return visitor.visit_children(self) -class VariableDeclaration(Declaration): - """ - 'var' fieldName (',' fieldName)* ':' typeDeclarator ('=' (sampleExpression | valueExp) )? NEWLINE; - """ - - def __init__(self, field_name, field_type): - super().__init__() - self.field_name = field_name - self.field_type = field_type - self.set_children(field_name) - - def enter_node(self, listener): - if hasattr(listener, "enter_variable_declaration"): - listener.enter_variable_declaration(self) - - def exit_node(self, listener): - if hasattr(listener, "exit_variable_declaration"): - listener.exit_variable_declaration(self) - - def accept(self, visitor): - if hasattr(visitor, "visit_variable_declaration"): - return visitor.visit_variable_declaration(self) - else: - return visitor.visit_children(self) - class KeepConstraintDeclaration(Declaration): def __init__(self, constraint_qualifier): @@ -1369,7 +1348,8 @@ def accept(self, visitor): class LogicalExpression(Expression): """ - In logical expressions, for the same operator, such as a=>b=>c, the operands of the expression are placed in children. + In logical expressions, for the same operator, such as a=>b=>c, + the operands of the expression are placed in children. It is not divided into multiple binary expressions like binary expressions """ diff --git a/srunner/osc2/ast_manager/ast_vistor.py b/srunner/osc2/ast_manager/ast_vistor.py index a0a46b2c5..017459754 100644 --- a/srunner/osc2/ast_manager/ast_vistor.py +++ b/srunner/osc2/ast_manager/ast_vistor.py @@ -141,9 +141,6 @@ def visit_named_argument(self, node: ast_node.NamedArgument): def visit_positional_argument(self, node: ast_node.PositionalArgument): return self.visit_children(node) - def visit_variable_declaration(self, node: ast_node.VariableDeclaration): - return self.visit_children(node) - def visit_keep_constraint_declaration( self, node: ast_node.KeepConstraintDeclaration ): diff --git a/srunner/osc2/osc2_parser/OpenSCENARIO2Parser.py b/srunner/osc2/osc2_parser/OpenSCENARIO2Parser.py index 4391103e6..b6442a509 100644 --- a/srunner/osc2/osc2_parser/OpenSCENARIO2Parser.py +++ b/srunner/osc2/osc2_parser/OpenSCENARIO2Parser.py @@ -12858,16 +12858,16 @@ def sIBaseExponent(self): else localctx.sIBaseUnitName.text ) if ( - not (unitName == "kg") - and not (unitName == "m") - and not (unitName == "s") - and not (unitName == "A") - and not (unitName == "K") - and not (unitName == "mol") - and not (unitName == "cd") - and not (unitName == "factor") - and not (unitName == "offset") - and not (unitName == "rad") + unitName != "kg" + and unitName != "m" + and unitName != "s" + and unitName != "A" + and unitName != "K" + and unitName != "mol" + and unitName != "cd" + and unitName != "factor" + and unitName != "offset" + and unitName != "rad" ): print("unit name %s is not supported" % unitName) raise NoViableAltException(self) @@ -16692,7 +16692,7 @@ def everyExpression(self): offsetName = ( None if localctx._Identifier is None else localctx._Identifier.text ) - if not (offsetName == "offset"): + if offsetName != "offset": print("%s must be offset" % offsetName) raise NoViableAltException(self) @@ -22502,7 +22502,7 @@ def integerLiteral(self): return localctx def sempred(self, localctx: RuleContext, ruleIndex: int, predIndex: int): - if self._predicates == None: + if self._predicates is None: self._predicates = dict() self._predicates[4] = self.structuredIdentifier_sempred self._predicates[116] = self.relation_sempred diff --git a/srunner/osc2/osc_preprocess/import_file.py b/srunner/osc2/osc_preprocess/import_file.py index cd2f8bda7..cef721224 100644 --- a/srunner/osc2/osc_preprocess/import_file.py +++ b/srunner/osc2/osc_preprocess/import_file.py @@ -17,9 +17,7 @@ def get_path(self): # Verify that it is the same file by comparing whether the paths are the same def same_as(self, another_file): - if self.__base_path == another_file.get_path(): - return True - return False + return self.__base_path == another_file.get_path() def get_true_path(self, import_file_path): """ @@ -88,9 +86,9 @@ def get_content(self): "[Error] file '" + self.get_path() + "' line " - + lines.__str__() + + str(lines) + ":" - + index.__str__() + + str(index) + " mismatched input ''" ) return content, lines diff --git a/srunner/osc2/osc_preprocess/pre_process.py b/srunner/osc2/osc_preprocess/pre_process.py index e3dc7e75c..39eedfaa6 100644 --- a/srunner/osc2/osc_preprocess/pre_process.py +++ b/srunner/osc2/osc_preprocess/pre_process.py @@ -23,16 +23,14 @@ def __init__(self, current_path): # Determine whether it is recorded def exit(self, current, note): - for member in note: - if current.same_as(member): - return True - return False + return any(current.same_as(member) for member in note) # Return import preprocessing results and import information def import_process(self): - self.file = open(self.result, "w+", encoding="utf-8") - current = ImportFile(self.current_path) - self.__import_process(current) + with open(self.result, "w+", encoding="utf-8") as f: + self.file = f + current = ImportFile(self.current_path) + self.__import_process(current) self.file.close() return self.result, self.import_msg diff --git a/srunner/osc2/symbol_manager/local_scope.py b/srunner/osc2/symbol_manager/local_scope.py index 2fa6af27f..600442d5a 100644 --- a/srunner/osc2/symbol_manager/local_scope.py +++ b/srunner/osc2/symbol_manager/local_scope.py @@ -8,10 +8,7 @@ def __init__(self, scope): # For local scopes, only internal naming conflicts are found def is_key_found(self, sym): - if sym.name and sym.name in self.symbols: - return True - else: - return False + return bool(sym.name and sym.name in self.symbols) def define(self, sym, ctx): if issubclass(type(sym), LocalScope): diff --git a/srunner/osc2/symbol_manager/qualifiedBehavior_symbol.py b/srunner/osc2/symbol_manager/qualifiedBehavior_symbol.py index 34dc5fe72..e58fcc662 100644 --- a/srunner/osc2/symbol_manager/qualifiedBehavior_symbol.py +++ b/srunner/osc2/symbol_manager/qualifiedBehavior_symbol.py @@ -26,12 +26,9 @@ def __init__(self, name, scope): # There is no nesting problem in actors, just look for actorName in the contained scope def is_actor_name_defined(self): - if self.actor_name == None: + if self.actor_name is None: return True - elif self.enclosing_scope.symbols.get(self.actor_name) is not None: - return True - else: - return False + return self.enclosing_scope.symbols.get(self.actor_name) is not None def is_qualified_behavior_name_valid(self, ctx): if self.actor_name == self.behavior_name and self.actor_name: @@ -44,7 +41,7 @@ def is_qualified_behavior_name_valid(self, ctx): elif self.is_actor_name_defined() is not True: error_msg = "actorName: " + self.actor_name + " is not defined!" LOG_ERROR(error_msg, ctx) - elif self.behavior_name == None: + elif self.behavior_name is None: error_msg = "behaviourName can not be empty!" LOG_ERROR(error_msg, ctx) else: diff --git a/srunner/osc2_dm/physical_types.py b/srunner/osc2_dm/physical_types.py index 68f0f0e7d..7a363fd42 100644 --- a/srunner/osc2_dm/physical_types.py +++ b/srunner/osc2_dm/physical_types.py @@ -33,10 +33,7 @@ def __neg__(self): return self def is_in_range(self, num) -> bool: - if num >= self.start and num < self.end: - return True - else: - return False + return num >= self.start and num < self.end def gen_single_value(self): return random.uniform(self.start, self.end) @@ -82,10 +79,7 @@ def is_in_range(self, value) -> bool: return value == self.num def is_single_value(self) -> bool: - if isinstance(self.num, Range): - return False - else: - return True + return isinstance(self.num, Range) def gen_single_value(self): if self.is_single_value(): diff --git a/srunner/scenarioconfigs/openscenario_configuration.py b/srunner/scenarioconfigs/openscenario_configuration.py index 7bd1b6d6a..2785d3a9f 100644 --- a/srunner/scenarioconfigs/openscenario_configuration.py +++ b/srunner/scenarioconfigs/openscenario_configuration.py @@ -359,10 +359,10 @@ def _get_actor_transform(self, actor_name): for private_action in self.init.iter("Private"): if private_action.attrib.get('entityRef', None) == actor_name: if actor_found: - # pylint: disable=line-too-long self.logger.warning( - " Warning: The actor '%s' was already assigned an initial position. Overwriting pose!", actor_name) - # pylint: enable=line-too-long + " Warning: The actor '%s' was already assigned an initial position. Overwriting pose!", + actor_name, + ) actor_found = True for position in private_action.iter('Position'): transform = OpenScenarioParser.convert_position_to_transform( @@ -371,10 +371,10 @@ def _get_actor_transform(self, actor_name): actor_transform = transform if not actor_found: - # pylint: disable=line-too-long self.logger.warning( - " Warning: The actor '%s' was not assigned an initial position. Using (0,0,0)", actor_name) - # pylint: enable=line-too-long + " Warning: The actor '%s' was not assigned an initial position. Using (0,0,0)", + actor_name, + ) return actor_transform def _get_actor_speed(self, actor_name): @@ -387,10 +387,10 @@ def _get_actor_speed(self, actor_name): for private_action in self.init.iter("Private"): if private_action.attrib.get('entityRef', None) == actor_name: if actor_found: - # pylint: disable=line-too-long self.logger.warning( - " Warning: The actor '%s' was already assigned an initial speed. Overwriting inital speed!", actor_name) - # pylint: enable=line-too-long + " Warning: The actor '%s' was already assigned an initial speed. Overwriting initial speed!", + actor_name, + ) actor_found = True for longitudinal_action in private_action.iter('LongitudinalAction'): @@ -401,8 +401,10 @@ def _get_actor_speed(self, actor_name): if speed >= 0: actor_speed = speed else: - raise AttributeError( - "Warning: Speed value of actor {} must be positive. Speed set to 0.".format(actor_name)) # pylint: disable=line-too-long + msg = "Warning: Speed value of actor {} must be positive. Speed set to 0.".format( + actor_name + ) + raise AttributeError(msg) return actor_speed def _validate_result(self): diff --git a/srunner/scenariomanager/actorcontrols/simple_vehicle_control.py b/srunner/scenariomanager/actorcontrols/simple_vehicle_control.py index 5f1d58daa..fd2e65d34 100644 --- a/srunner/scenariomanager/actorcontrols/simple_vehicle_control.py +++ b/srunner/scenariomanager/actorcontrols/simple_vehicle_control.py @@ -115,7 +115,12 @@ def __init__(self, actor, args=None): bp.set_attribute('hit_radius', '1') bp.set_attribute('only_dynamics', 'True') self._obstacle_sensor = CarlaDataProvider.get_world().spawn_actor( - bp, carla.Transform(carla.Location(x=self._actor.bounding_box.extent.x, z=1.0)), attach_to=self._actor) + bp, + carla.Transform( + carla.Location(x=self._actor.bounding_box.extent.x, z=1.0) + ), + attach_to=self._actor, + ) self._obstacle_sensor.listen(lambda event: self._on_obstacle(event)) # pylint: disable=unnecessary-lambda if args and 'consider_trafficlights' in args and strtobool(args['consider_trafficlights']): diff --git a/srunner/scenariomanager/carla_data_provider.py b/srunner/scenariomanager/carla_data_provider.py index 9e5e23d39..a2b15ee4a 100644 --- a/srunner/scenariomanager/carla_data_provider.py +++ b/srunner/scenariomanager/carla_data_provider.py @@ -59,7 +59,8 @@ class CarlaDataProvider(object): # pylint: disable=too-many-public-methods _map = None # type: carla.Map _sync_flag = False # type: bool _spawn_points = None # type: list[carla.Transform] - _spawn_index = 0 + _spawn_index = 0 # type: int + """Index of spawn points that have been used""" _blueprint_library = None # type: carla.BlueprintLibrary _all_actors = None # type: carla.ActorList _ego_vehicle_route = None @@ -74,10 +75,12 @@ class CarlaDataProvider(object): # pylint: disable=too-many-public-methods @staticmethod def set_local_planner(plan): + """Register a local planner""" CarlaDataProvider._local_planner = plan @staticmethod def get_local_planner(): + """Access the local planner. Needs to call `set_local_planner` before""" return CarlaDataProvider._local_planner @staticmethod @@ -415,7 +418,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 = [] @@ -501,7 +504,12 @@ def generate_spawn_points(): CarlaDataProvider._spawn_index = 0 @staticmethod - def check_road_length(wp, length: float): + def check_road_length(wp: carla.Waypoint, length: float): + """ + Checks wether the road starting at the given waypoint is at least the given length long. + + This is done by querying waypoints in 5m steps checking their road_id and lane_id. + """ waypoint_separation = 5 cur_len = 0 @@ -525,6 +533,16 @@ def check_road_length(wp, length: float): @staticmethod def get_road_lanes(wp): # type: (carla.Waypoint) -> list[carla.Waypoint] + """ + This function takes a waypoint and returns a list of waypoints representing + all the parallel driving lanes from the leftmost to the rightmost lane. + + Args: + wp (carla.Waypoint): The starting waypoint. + + Returns: + list[carla.Waypoint]: A list of waypoints representing all driving lanes. + """ if wp.is_junction: return [] # find the most left lane's waypoint @@ -561,11 +579,25 @@ def get_road_lanes(wp): @staticmethod def get_road_lane_cnt(wp): + """ + Counts the number of parallel driving lanes at the given waypoint. + """ lanes = CarlaDataProvider.get_road_lanes(wp) return len(lanes) @staticmethod def get_waypoint_by_laneid(lane_num: int): + """ + Selects an unused spawn point und by using `get_road_lanes` returns a parallel waypoint. + + Args: + lane_num (int): The lane number to select, 1 is the leftmost lane. + Use 0 and negative to count from the rightmost lane. + + Returns: + carla.Waypoint | None: The selected waypoint. None if no more spawn points are available + or if `lane_num``is higher than the number of lanes. + """ if CarlaDataProvider._spawn_points is None: CarlaDataProvider.generate_spawn_points() @@ -575,7 +607,9 @@ def get_waypoint_by_laneid(lane_num: int): else: pos = CarlaDataProvider._spawn_points[CarlaDataProvider._spawn_index] # pylint: disable=unsubscriptable-object CarlaDataProvider._spawn_index += 1 - wp = CarlaDataProvider.get_map().get_waypoint(pos.location, project_to_road=True, lane_type=carla.LaneType.Driving) + wp = CarlaDataProvider.get_map().get_waypoint( + pos.location, project_to_road=True, lane_type=carla.LaneType.Driving + ) road_lanes = CarlaDataProvider.get_road_lanes(wp) @@ -598,7 +632,7 @@ def check_attribute_value(blueprint, name, value): if not blueprint.has_attribute(name): return False - attribute_type = blueprint.get_attribute(key).type + attribute_type = blueprint.get_attribute(name).type if attribute_type == carla.ActorAttributeType.Bool: return blueprint.get_attribute(name).as_bool() == value elif attribute_type == carla.ActorAttributeType.Int: @@ -622,7 +656,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 @@ -706,36 +740,43 @@ def handle_actor_batch(batch, tick=True): return actors @staticmethod - def spawn_actor(bp, spawn_point, must_spawn=False, track_physics=None, attach_to=None, attachment_type=carla.AttachmentType.Rigid): + def spawn_actor( + bp, + spawn_point, + must_spawn=False, + track_physics=None, + attach_to=None, + attachment_type=carla.AttachmentType.Rigid, + ): # type: (carla.ActorBlueprint, carla.Waypoint | carla.Transform, bool, bool | None, carla.Actor | None, carla.AttachmentType) -> carla.Actor | None # pylint: disable=line-too-long """ The method will spawn and return an actor. The actor will need an available blueprint to be created. - It can also be attached to a parent with a certain attachment type. + It can also be attached to a parent with a certain attachment type. Args: bp (carla.ActorBlueprint): The blueprint of the actor to spawn. spawn_point (carla.Transform): The spawn point of the actor. - must_spawn (bool, optional): + must_spawn (bool, optional): If True, the actor will be spawned or an exception will be raised. If False, the function returns None if the actor could not be spawned. Defaults to False. - track_physics (bool | None, optional): - If True, `get_location`, `get_transform` and `get_velocity` + track_physics (bool | None, optional): + If True, `get_location`, `get_transform` and `get_velocity` can be used for this actor. If None, the actor will be tracked if it is a Vehicle or Walker. Defaults to None. - attach_to (carla.Actor | None, optional): - The parent object that the spawned actor will follow around. + attach_to (carla.Actor | None, optional): + The parent object that the spawned actor will follow around. Defaults to None. - attachment_type (carla.AttachmentType, optional): - Determines how fixed and rigorous should be the changes in position + attachment_type (carla.AttachmentType, optional): + Determines how fixed and rigorous should be the changes in position according to its parent object. Defaults to carla.AttachmentType.Rigid. 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. """ @@ -990,6 +1031,10 @@ def get_actor_by_id(actor_id): @staticmethod def get_actor_by_name(role_name: str): + """ + Queries the actor pool for an actor with the given role name. + Returns the first actor matching actor. + """ for actor_id in CarlaDataProvider._carla_actor_pool: if CarlaDataProvider._carla_actor_pool[actor_id].attributes['role_name'] == role_name: @@ -1004,7 +1049,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)) @@ -1094,5 +1139,9 @@ def cleanup(): @property def world(self): + """ + Return world + + This is a read-only property of `get_world` + """ return self._world - diff --git a/srunner/scenariomanager/lights_sim.py b/srunner/scenariomanager/lights_sim.py index 316def239..f4c6e041a 100644 --- a/srunner/scenariomanager/lights_sim.py +++ b/srunner/scenariomanager/lights_sim.py @@ -83,10 +83,7 @@ def _get_night_mode(self, weather): joined_threshold += int(cloudiness_dist < self.COMBINED_THRESHOLD) joined_threshold += int(fog_density_dist < self.COMBINED_THRESHOLD) - if joined_threshold >= 2: - return True - - return False + return joined_threshold >= 2 def _turn_close_lights_on(self, location): """Turns on the lights of all the objects close to the ego vehicle""" diff --git a/srunner/scenariomanager/scenarioatomics/atomic_behaviors.py b/srunner/scenariomanager/scenarioatomics/atomic_behaviors.py index cd1a20fe3..776b5a72c 100644 --- a/srunner/scenariomanager/scenarioatomics/atomic_behaviors.py +++ b/srunner/scenariomanager/scenarioatomics/atomic_behaviors.py @@ -104,7 +104,7 @@ def __init__(self, name, actor=None): """ Default init. Has to be called via super from derived class """ - super(AtomicBehavior, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self.name = name self._actor = actor @@ -163,7 +163,7 @@ def __init__(self, script, base_path=None, name="RunScript"): """ Setup parameters """ - super(RunScript, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._script = script self._base_path = base_path @@ -200,7 +200,7 @@ class ChangeParameter(AtomicBehavior): """ def __init__(self, parameter_ref, value, rule=None, name="ChangeParameter"): - super(ChangeParameter, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % self.__class__.__name__) self._parameter_ref = parameter_ref self._rule = rule @@ -247,7 +247,7 @@ def __init__(self, weather, name="ChangeWeather"): """ Setup parameters """ - super(ChangeWeather, self).__init__(name) + super().__init__(name) self._weather = weather def update(self): @@ -281,7 +281,7 @@ def __init__(self, friction, name="ChangeRoadFriction"): """ Setup parameters """ - super(ChangeRoadFriction, self).__init__(name) + super().__init__(name) self._friction = friction def update(self): @@ -335,7 +335,7 @@ def __init__(self, actor, control_py_module, args, scenario_file_path=None, name """ Setup actor controller. """ - super(ChangeActorControl, self).__init__(name, actor) + super().__init__(name, actor) self._actor_control = ActorControl(actor, control_py_module=control_py_module, args=args, scenario_file_path=scenario_file_path) @@ -383,7 +383,7 @@ def __init__(self, name="UpdateAllActorControls"): """ Constructor """ - super(UpdateAllActorControls, self).__init__(name) + super().__init__(name) def update(self): """ @@ -464,7 +464,7 @@ def __init__(self, actor, target_speed, init_speed=False, """ Setup parameters """ - super(ChangeActorTargetSpeed, self).__init__(name, actor) + super().__init__(name, actor) self._target_speed = target_speed self._init_speed = init_speed @@ -495,7 +495,7 @@ def initialise(self): except AttributeError: pass - if not actor_dict or not self._actor.id in actor_dict: + if not actor_dict or self._actor.id not in actor_dict: raise RuntimeError("Actor not found in ActorsWithController BlackBoard") self._start_time = GameTime.get_time() @@ -517,7 +517,7 @@ def initialise(self): if self._init_speed: actor_dict[self._actor.id].set_init_speed() - super(ChangeActorTargetSpeed, self).initialise() + super().initialise() def update(self): """ @@ -535,7 +535,7 @@ def update(self): except AttributeError: pass - if not actor_dict or not self._actor.id in actor_dict: + if not actor_dict or self._actor.id not in actor_dict: return py_trees.common.Status.FAILURE if actor_dict[self._actor.id].get_last_longitudinal_command() != self._start_time: @@ -597,7 +597,7 @@ def __init__(self, actor, master_actor, actor_target, master_target, final_speed """ Setup required parameters """ - super(SyncArrivalOSC, self).__init__(name, actor) + super().__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor @@ -627,7 +627,7 @@ def initialise(self): except AttributeError: pass - if not actor_dict or not self._actor.id in actor_dict: + if not actor_dict or self._actor.id not in actor_dict: raise RuntimeError("Actor not found in ActorsWithController BlackBoard") self._start_time = GameTime.get_time() @@ -662,7 +662,7 @@ def update(self): except AttributeError: pass - if not actor_dict or not self._actor.id in actor_dict: + if not actor_dict or self._actor.id not in actor_dict: return py_trees.common.Status.FAILURE if actor_dict[self._actor.id].get_last_longitudinal_command() != self._start_time: @@ -717,6 +717,9 @@ def terminate(self, new_status): final_speed = master_speed * self._final_speed else: print("'relative_type' must be delta or factor") + self._final_speed_set = True + super().terminate(new_status) + return else: final_speed = self._final_speed @@ -724,7 +727,7 @@ def terminate(self, new_status): self._final_speed_set = True - super(SyncArrivalOSC, self).terminate(new_status) + super().terminate(new_status) class ChangeActorWaypoints(AtomicBehavior): @@ -759,7 +762,7 @@ def __init__(self, actor, waypoints, times=None, name="ChangeActorWaypoints"): """ Setup parameters """ - super(ChangeActorWaypoints, self).__init__(name, actor) + super().__init__(name, actor) self._waypoints = waypoints self._start_time = None @@ -782,7 +785,7 @@ def initialise(self): except AttributeError: pass - if not actor_dict or not self._actor.id in actor_dict: + if not actor_dict or self._actor.id not in actor_dict: raise RuntimeError("Actor not found in ActorsWithController BlackBoard") self._start_time = GameTime.get_time() @@ -839,7 +842,7 @@ def initialise(self): actor_dict[self._actor.id].update_waypoints(route, start_time=self._start_time) - super(ChangeActorWaypoints, self).initialise() + super().initialise() def update(self): """ @@ -857,7 +860,7 @@ def update(self): except AttributeError: pass - if not actor_dict or not self._actor.id in actor_dict: + if not actor_dict or self._actor.id not in actor_dict: return py_trees.common.Status.FAILURE actor = actor_dict[self._actor.id] @@ -916,7 +919,7 @@ def __init__(self, actor, position, name="ChangeActorWaypointsToReachPosition"): """ Setup parameters """ - super(ChangeActorWaypointsToReachPosition, self).__init__(actor, []) + super().__init__(actor, []) self._end_transform = position @@ -943,7 +946,7 @@ def initialise(self): for elem in plan: self._waypoints.append(elem[0].transform) - super(ChangeActorWaypointsToReachPosition, self).initialise() + super().initialise() class ChangeActorLateralMotion(AtomicBehavior): @@ -993,7 +996,7 @@ def __init__(self, actor, direction='left', distance_lane_change=25, distance_ot """ Setup parameters """ - super(ChangeActorLateralMotion, self).__init__(name, actor) + super().__init__(name, actor) self._waypoints = [] self._direction = direction @@ -1025,7 +1028,7 @@ def initialise(self): except AttributeError: pass - if not actor_dict or not self._actor.id in actor_dict: + if not actor_dict or self._actor.id not in actor_dict: raise RuntimeError("Actor not found in ActorsWithController BlackBoard") self._start_time = GameTime.get_time() @@ -1044,7 +1047,7 @@ def initialise(self): actor_dict[self._actor.id].update_waypoints(self._waypoints, start_time=self._start_time) - super(ChangeActorLateralMotion, self).initialise() + super().initialise() def update(self): """ @@ -1063,7 +1066,7 @@ def update(self): except AttributeError: pass - if not actor_dict or not self._actor.id in actor_dict: + if not actor_dict or self._actor.id not in actor_dict: return py_trees.common.Status.FAILURE if not self._plan: @@ -1143,7 +1146,7 @@ def __init__(self, actor, offset, relative_actor=None, continuous=True, name="Ch """ Setup parameters """ - super(ChangeActorLaneOffset, self).__init__(name, actor) + super().__init__(name, actor) self._offset = offset self._relative_actor = relative_actor @@ -1171,14 +1174,14 @@ def initialise(self): except AttributeError: pass - if not actor_dict or not self._actor.id in actor_dict: + if not actor_dict or self._actor.id not in actor_dict: raise RuntimeError("Actor not found in ActorsWithController BlackBoard") self._start_time = GameTime.get_time() actor_dict[self._actor.id].update_offset(self._offset, start_time=self._start_time) - super(ChangeActorLaneOffset, self).initialise() + super().initialise() def update(self): """ @@ -1196,7 +1199,7 @@ def update(self): except AttributeError: pass - if not actor_dict or not self._actor.id in actor_dict: + if not actor_dict or self._actor.id not in actor_dict: return py_trees.common.Status.FAILURE if actor_dict[self._actor.id].get_last_lane_offset_command() != self._start_time: @@ -1273,7 +1276,7 @@ def terminate(self, new_status): self._overwritten = True - super(ChangeActorLaneOffset, self).terminate(new_status) + super().terminate(new_status) class ChangeLateralDistance(AtomicBehavior): @@ -1315,7 +1318,7 @@ def __init__(self, actor, offset, relative_actor=None, freespace=False, """ Setup parameters """ - super(ChangeLateralDistance, self).__init__(name, actor) + super().__init__(name, actor) self._offset = offset self._relative_actor = relative_actor @@ -1359,7 +1362,7 @@ def initialise(self): actor_dict[self._actor.id].update_offset(self._offset, start_time=self._start_time) - super(ChangeLateralDistance, self).initialise() + super().initialise() def update(self): """ @@ -1454,7 +1457,7 @@ def terminate(self, new_status): self._overwritten = True - super(ChangeLateralDistance, self).terminate(new_status) + super().terminate(new_status) class ActorTransformSetterToOSCPosition(AtomicBehavior): @@ -1481,14 +1484,14 @@ def __init__(self, actor, osc_position, physics=True, name="ActorTransformSetter """ Setup parameters """ - super(ActorTransformSetterToOSCPosition, self).__init__(name, actor) + super().__init__(name, actor) self._osc_position = osc_position self._physics = physics self._osc_transform = None def initialise(self): - super(ActorTransformSetterToOSCPosition, self).initialise() + super().initialise() if self._actor.is_alive: self._actor.set_target_velocity(carla.Vector3D(0, 0, 0)) @@ -1536,7 +1539,7 @@ def __init__(self, actor, throttle_value, target_velocity, name="Acceleration"): Setup parameters including acceleration value (via throttle_value) and target velocity """ - super(AccelerateToVelocity, self).__init__(name, actor) + super().__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._control, self._type = get_actor_control(actor) self._throttle_value = throttle_value @@ -1548,7 +1551,7 @@ def initialise(self): self._control.speed = self._target_velocity self._control.direction = CarlaDataProvider.get_transform(self._actor).get_forward_vector() - super(AccelerateToVelocity, self).initialise() + super().initialise() def update(self): """ @@ -1592,7 +1595,7 @@ def __init__(self, actor, start_velocity, target_velocity, acceleration, start_t Setup parameters including acceleration value (via throttle_value), start_velocity, target velocity and duration """ - super(UniformAcceleration, self).__init__(name, actor) + super().__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._control, self._type = get_actor_control(actor) self._start_velocity = start_velocity @@ -1608,7 +1611,7 @@ def initialise(self): self._control.speed = self._start_velocity self._control.direction = CarlaDataProvider.get_transform(self._actor).get_forward_vector() - super(UniformAcceleration, self).initialise() + super().initialise() def update(self): """ @@ -1656,7 +1659,7 @@ def __init__(self, actor, target_velocity, name="ChangeTargetSpeed"): Setup parameters including acceleration value (via throttle_value) and target velocity """ - super(ChangeTargetSpeed, self).__init__(name, actor) + super().__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._control, self._type = get_actor_control(actor) self._target_velocity = target_velocity @@ -1667,7 +1670,7 @@ def initialise(self): self._control.speed = self._target_velocity self._control.direction = CarlaDataProvider.get_transform(self._actor).get_forward_vector() - super(ChangeTargetSpeed, self).initialise() + super().initialise() def update(self): """ @@ -1719,7 +1722,7 @@ def __init__(self, actor, brake_value, target_velocity, name="Deceleration"): Setup parameters including acceleration value (via throttle_value) and target velocity """ - super(DecelerateToVelocity, self).__init__(name, actor) + super().__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._control, self._type = get_actor_control(actor) self._brake_value = brake_value @@ -1731,7 +1734,7 @@ def initialise(self): self._control.speed = self._target_velocity self._control.direction = CarlaDataProvider.get_transform(self._actor).get_forward_vector() - super(DecelerateToVelocity, self).initialise() + super().initialise() def update(self): """ @@ -1781,7 +1784,7 @@ def __init__(self, actor, other_actor, throttle_value=1, delta_velocity=10, trig Setup parameters The target_speet is calculated on the fly. """ - super(AccelerateToCatchUp, self).__init__(name, actor) + super().__init__(name, actor) self._other_actor = other_actor self._throttle_value = throttle_value @@ -1797,7 +1800,7 @@ def initialise(self): # get initial actor position self._initial_actor_pos = CarlaDataProvider.get_location(self._actor) - super(AccelerateToCatchUp, self).initialise() + super().initialise() def update(self): @@ -1859,7 +1862,7 @@ def __init__(self, actor, target_velocity, force_speed=False, Setup parameters including acceleration value (via throttle_value) and target velocity """ - super(KeepVelocity, self).__init__(name, actor) + super().__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._target_velocity = target_velocity @@ -1887,7 +1890,7 @@ def initialise(self): self._control.hand_brake = False self._actor.apply_control(self._control) - super(KeepVelocity, self).initialise() + super().initialise() def update(self): """ @@ -1940,7 +1943,7 @@ def terminate(self, new_status): self._actor.apply_control(self._control) except RuntimeError: pass - super(KeepVelocity, self).terminate(new_status) + super().terminate(new_status) class ChangeAutoPilot(AtomicBehavior): @@ -1963,7 +1966,7 @@ def __init__(self, actor, activate, parameters=None, name="ChangeAutoPilot"): """ Setup parameters """ - super(ChangeAutoPilot, self).__init__(name, actor) + super().__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._activate = activate self._tm = CarlaDataProvider.get_client().get_trafficmanager( @@ -2025,7 +2028,7 @@ def __init__(self, actor, brake_value, name="Stopping"): """ Setup _actor and maximum braking value """ - super(StopVehicle, self).__init__(name, actor) + super().__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._control, self._type = get_actor_control(actor) if self._type == 'walker': @@ -2075,7 +2078,7 @@ def __init__(self, actor, actor_reference, target_location, gain=1, name="SyncAr """ Setup required parameters """ - super(SyncArrival, self).__init__(name, actor) + super().__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._control = carla.VehicleControl() self._actor_reference = actor_reference @@ -2127,7 +2130,7 @@ def terminate(self, new_status): self._control.throttle = 0.0 self._control.brake = 0.0 self._actor.apply_control(self._control) - super(SyncArrival, self).terminate(new_status) + super().terminate(new_status) class SyncArrivalWithAgent(AtomicBehavior): @@ -2252,6 +2255,7 @@ def __init__(self, actor, reference_actor, direction, speed_perc=100, self._map = CarlaDataProvider.get_map() self._grp = CarlaDataProvider.get_global_route_planner() + self._agent = None def initialise(self): """Initialises the agent""" @@ -2296,7 +2300,7 @@ def __init__(self, actor, steer_value, throttle_value, name="Jittering"): """ Setup actor , maximum steer value and throttle value """ - super(AddNoiseToVehicle, self).__init__(name, actor) + super().__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._control = carla.VehicleControl() self._steer_value = steer_value @@ -2382,7 +2386,7 @@ def __init__(self, new_steer_noise, new_throttle_noise, """ Setup actor , maximum steer value and throttle value """ - super(ChangeNoiseParameters, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._new_steer_noise = new_steer_noise self._new_throttle_noise = new_throttle_noise @@ -2418,11 +2422,19 @@ class BasicAgentBehavior(AtomicBehavior): The behavior terminates after reaching the target_location (within 2 meters) """ - def __init__(self, actor, target_location=None, plan=None, target_speed=20, opt_dict=None, name="BasicAgentBehavior"): + def __init__( + self, + actor, + target_location=None, + plan=None, + target_speed=20, + opt_dict=None, + name="BasicAgentBehavior", + ): """ Setup actor and maximum steer value """ - super(BasicAgentBehavior, self).__init__(name, actor) + super().__init__(name, actor) self._map = CarlaDataProvider.get_map() self._target_location = target_location self._target_speed = target_speed @@ -2463,7 +2475,7 @@ def terminate(self, new_status): self._control.throttle = 0.0 self._control.brake = 0.0 self._actor.apply_control(self._control) - super(BasicAgentBehavior, self).terminate(new_status) + super().terminate(new_status) class ConstantVelocityAgentBehavior(AtomicBehavior): @@ -2486,7 +2498,7 @@ def __init__(self, actor, target_location, target_speed=None, """ Set up actor and local planner """ - super(ConstantVelocityAgentBehavior, self).__init__(name, actor) + super().__init__(name, actor) self._target_speed = target_speed self._map = CarlaDataProvider.get_map() self._target_location = target_location @@ -2529,7 +2541,7 @@ def terminate(self, new_status): self._actor.apply_control(self._control) if self._agent: self._agent.destroy_sensor() - super(ConstantVelocityAgentBehavior, self).terminate(new_status) + super().terminate(new_status) class AdaptiveConstantVelocityAgentBehavior(AtomicBehavior): @@ -2621,7 +2633,7 @@ def __init__(self, duration=float("inf"), name="Idle"): """ Setup actor """ - super(Idle, self).__init__(name) + super().__init__(name) self._duration = duration self._start_time = 0 self.logger.debug("%s.__init__()" % (self.__class__.__name__)) @@ -2631,7 +2643,7 @@ def initialise(self): Set start time """ self._start_time = GameTime.get_time() - super(Idle, self).initialise() + super().initialise() def update(self): """ @@ -2714,7 +2726,7 @@ def __init__(self, actor, target_speed=None, plan=None, blackboard_queue_name=No """ Set up actor and local planner """ - super(WaypointFollower, self).__init__(name, actor) + super().__init__(name, actor) self._actor_dict = {} self._actor_dict[actor] = None self._target_speed = target_speed @@ -2726,6 +2738,7 @@ def __init__(self, actor, target_speed=None, plan=None, blackboard_queue_name=No self._queue = Blackboard().get(blackboard_queue_name) self._args_lateral_dict = {'K_P': 1.0, 'K_D': 0.01, 'K_I': 0.0, 'dt': 0.05} self._avoid_collision = avoid_collision + self._start_time = None self._unique_id = 0 def initialise(self): @@ -2735,7 +2748,7 @@ def initialise(self): Checks if another WaypointFollower behavior is already running for this actor. If this is the case, a termination signal is sent to the running behavior. """ - super(WaypointFollower, self).initialise() + super().initialise() self._start_time = GameTime.get_time() self._unique_id = int(round(time.time() * 1e9)) try: @@ -2886,7 +2899,7 @@ def terminate(self, new_status): self._local_planner_dict = {} self._actor_dict = {} - super(WaypointFollower, self).terminate(new_status) + super().terminate(new_status) class LaneChange(WaypointFollower): @@ -2931,7 +2944,7 @@ def __init__(self, actor, speed=10, direction='left', distance_same_lane=5, dist self._pos_before_lane_change = None self._plan = None - super(LaneChange, self).__init__(actor, target_speed=speed, name=name) + super().__init__(actor, target_speed=speed, name=name) def initialise(self): @@ -2942,7 +2955,7 @@ def initialise(self): self._plan, self._target_lane_id = generate_target_waypoint_list_multilane( position_actor, self._direction, self._distance_same_lane, self._distance_other_lane, self._distance_lane_change, check=True, lane_changes=self._lane_changes) - super(LaneChange, self).initialise() + super().initialise() def update(self): @@ -2950,7 +2963,7 @@ def update(self): print("{} couldn't perform the expected lane change".format(self._actor)) return py_trees.common.Status.FAILURE - status = super(LaneChange, self).update() + status = super().update() current_position_actor = CarlaDataProvider.get_map().get_waypoint(self._actor.get_location()) current_lane_id = current_position_actor.lane_id @@ -2981,7 +2994,7 @@ def __init__(self, actor, init_speed=10, name='SetInitSpeed'): self._terminate = None self._actor = actor - super(SetInitSpeed, self).__init__(name, actor) + super().__init__(name, actor) def initialise(self): """ @@ -3020,7 +3033,7 @@ def __init__(self, vehicle, hand_brake_value, name="Braking"): """ Setup vehicle control and brake value """ - super(HandBrakeVehicle, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._vehicle = vehicle self._control, self._type = get_actor_control(vehicle) @@ -3059,7 +3072,7 @@ def __init__(self, actor, name="ActorDestroy"): """ Setup actor """ - super(ActorDestroy, self).__init__(name, actor) + super().__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) def update(self): @@ -3096,7 +3109,7 @@ def __init__(self, actor, transform, physics=True, name="ActorTransformSetter"): """ Init """ - super(ActorTransformSetter, self).__init__(name, actor) + super().__init__(name, actor) self._transform = transform self._physics = physics self.logger.debug("%s.__init__()" % (self.__class__.__name__)) @@ -3106,7 +3119,7 @@ def initialise(self): self._actor.set_target_velocity(carla.Vector3D(0, 0, 0)) self._actor.set_target_angular_velocity(carla.Vector3D(0, 0, 0)) self._actor.set_transform(self._transform) - super(ActorTransformSetter, self).initialise() + super().initialise() def update(self): """ @@ -3178,7 +3191,7 @@ def __init__(self, actor, state, name="TrafficLightStateSetter"): """ Init """ - super(TrafficLightStateSetter, self).__init__(name) + super().__init__(name) self._actor = actor if "traffic_light" in actor.type_id else None self._state = state @@ -3217,7 +3230,7 @@ def __init__(self, traffic_signal_id, state, duration, delay=None, ref_id=None, """ Init """ - super(TrafficLightControllerSetter, self).__init__(name) + super().__init__(name) self.actor_id = traffic_signal_id self._actor = None self._start_time = None @@ -3250,6 +3263,7 @@ def initialise(self): } self._actor.set_state(self._state) self._actor.set_green_time(self.duration_time) + return None def update(self): """Waits until the adequate time has passed""" @@ -3274,7 +3288,7 @@ def terminate(self, new_status): self._actor.set_red_time(self._previous_traffic_light_info[self._actor]['red_time']) self._actor.set_yellow_time(self._previous_traffic_light_info[self._actor]['yellow_time']) - super(TrafficLightControllerSetter, self).terminate(new_status) + super().terminate(new_status) class ActorSource(AtomicBehavior): @@ -3299,7 +3313,7 @@ def __init__(self, actor_type_list, transform, threshold, blackboard_queue_name, """ Setup class members """ - super(ActorSource, self).__init__(name) + super().__init__(name) self._world = CarlaDataProvider.get_world() self._actor_types = actor_type_list self._spawn_point = transform @@ -3318,7 +3332,7 @@ def update(self): spawn_point_blocked = True if not spawn_point_blocked: - for actor in world_actors: + for actor in world_actors: # pylint: disable=not-an-iterable if self._spawn_point.location.distance(actor.get_location()) < self._threshold: spawn_point_blocked = True self._last_blocking_actor = actor @@ -3353,7 +3367,7 @@ def __init__(self, sink_location, threshold, name="ActorSink"): """ Setup class members """ - super(ActorSink, self).__init__(name) + super().__init__(name) self._sink_location = sink_location self._threshold = threshold @@ -3457,6 +3471,7 @@ def _spawn_actor(self, transform): self._tm.ignore_signs_percentage(actor, 100) self._collision_sensor_list.append(sensor) self._actor_list.append(actor) + return None def update(self): """Controls the created actors and creaes / removes other when needed""" @@ -3569,6 +3584,19 @@ def __init__(self, reference_wp, reference_actor, spawn_dist_interval, self._terminated = False + # initialise attributes + self._speed = None # Km / h + self._flow_distance = -1.0 + + self._sink_wp = None + self._source_wp = None + + self._source_transform = None + self._source_location = None + self._sink_location = None + + self._route = None + def _move_waypoint_forward(self, wp, distance): """Moves forward a certain distance, stopping at junctions""" dist = 0 @@ -3624,6 +3652,7 @@ def _spawn_actor(self): self._actor_list.append([actor, controller]) self._spawn_dist = self._rng.uniform(self._min_spawn_dist, self._max_spawn_dist) + return None def update(self): """Controls the created actors and creates / removes other when needed""" @@ -3721,6 +3750,9 @@ def __init__(self, source_wp, sink_wp, reference_actor, spawn_dist, self._map = CarlaDataProvider.get_map() self._terminated = False + # Initialise attributes + self._speed = None + self._route = None def initialise(self): """Get the actor flow source and sink, depending on the reference actor speed""" @@ -3739,6 +3771,7 @@ def _spawn_actor(self): controller = BasicAgent(actor, self._speed, self._opt_dict, self._map, self._grp) controller.set_global_plan(self._route) self._actor_list.append([actor, controller]) + return None def update(self): """Controls the created actors and creates / removes other when needed""" @@ -3947,7 +3980,7 @@ def __init__(self, actor, vehicle_door, name="OpenVehicleDoor"): """ Setup class members """ - super(OpenVehicleDoor, self).__init__(name, actor) + super().__init__(name, actor) self._vehicle_door = vehicle_door self.logger.debug("%s.__init__()" % (self.__class__.__name__)) @@ -3979,7 +4012,7 @@ class TrafficLightFreezer(AtomicBehavior): def __init__(self, traffic_lights_dict, duration=10000, name="TrafficLightFreezer"): """Setup class members""" - super(TrafficLightFreezer, self).__init__(name) + super().__init__(name) self._traffic_lights_dict = traffic_lights_dict self._duration = duration self._previous_traffic_light_info = {} @@ -4040,7 +4073,7 @@ def __init__(self, recorder_name, name="StartRecorder"): """ Setup class members """ - super(StartRecorder, self).__init__(name) + super().__init__(name) self._client = CarlaDataProvider.get_client() self._recorder_name = recorder_name @@ -4062,7 +4095,7 @@ def __init__(self, name="StopRecorder"): """ Setup class members """ - super(StopRecorder, self).__init__(name) + super().__init__(name) self._client = CarlaDataProvider.get_client() def update(self): @@ -4123,7 +4156,7 @@ class TrafficLightManipulator(AtomicBehavior): } def __init__(self, ego_vehicle, subtype, debug=False, name="TrafficLightManipulator"): - super(TrafficLightManipulator, self).__init__(name) + super().__init__(name) self.ego_vehicle = ego_vehicle self.subtype = subtype self.current_step = 1 @@ -4372,7 +4405,7 @@ def __init__(self, actor, route, blackboard_list, distance, debug=False, name="S """ Setup class members """ - super(ScenarioTriggerer, self).__init__(name) + super().__init__(name) self._world = CarlaDataProvider.get_world() self._map = CarlaDataProvider.get_map() self._debug = debug @@ -4480,7 +4513,7 @@ def __init__(self, actor, reference_actor, gap, gap_type="distance", max_speed=N """ Setup parameters """ - super(KeepLongitudinalGap, self).__init__(name, actor) + super().__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._reference_actor = reference_actor self._gap = gap @@ -4512,7 +4545,7 @@ def initialise(self): self._global_rp = CarlaDataProvider.get_global_route_planner() - super(KeepLongitudinalGap, self).initialise() + super().initialise() def update(self): """ @@ -4579,7 +4612,7 @@ def __init__(self, actor_type, transform, color=None, name="SpawnActor"): """ Setup class members """ - super(AddActor, self).__init__(name) + super().__init__(name) self._actor_type = actor_type self._spawn_point = transform self._color = color @@ -4591,11 +4624,11 @@ def update(self): self._actor_type, self._spawn_point, color=self._color) if new_actor: new_status = py_trees.common.Status.SUCCESS - except: # pylint: disable=bare-except + except RuntimeError: print("ActorSource unable to spawn actor") - new_status = py_trees.common.Status.FAILURE - finally: - return new_status + return py_trees.common.Status.FAILURE + return new_status + class SwitchWrongDirectionTest(AtomicBehavior): @@ -4620,6 +4653,14 @@ def update(self): class SwitchMinSpeedCriteria(AtomicBehavior): + """ + Atomic that switch the SwitchMinSpeedCriteria criterion. + + Args: + active (bool): True: activated; False: deactivated + name (str): name of the behavior + """ + def __init__(self, active, name="ChangeMinSpeed"): """ @@ -4655,12 +4696,21 @@ 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"): + + def __init__( + self, + source_location, + sink_locations, + sink_locations_prob, + spawn_dist_interval, + random_seed=None, + sink_dist=2, + name="WalkerFlow", + ): """ Setup class members """ - super(WalkerFlow, self).__init__(name) + super().__init__(name) if random_seed is not None: self._rng = random.RandomState(random_seed) @@ -4755,7 +4805,7 @@ def __init__(self, source_location, sink_location, """ Setup class members """ - super(AIWalkerBehavior, self).__init__(name) + super().__init__(name) self._world = CarlaDataProvider.get_world() self._controller_bp = self._world.get_blueprint_library().find('controller.ai.walker') @@ -4788,7 +4838,7 @@ def initialise(self): self._controller.start() self._controller.go_to_location(self._sink_location) - super(AIWalkerBehavior, self).initialise() + super().initialise() def update(self): """Controls the created walker""" @@ -4823,7 +4873,7 @@ class ScenarioTimeout(AtomicBehavior): """ This class is an idle behavior that waits for a set amount of time - before stoping. + before stopping. It is meant to be used with the `ScenarioTimeoutTest` to be used at scenarios that block the ego's route (such as adding obstacles) so that if the ego is @@ -4871,8 +4921,14 @@ 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("AC_SwitchActorBlockedTest", True, 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..2e87da2d3 100644 --- a/srunner/scenariomanager/scenarioatomics/atomic_criteria.py +++ b/srunner/scenariomanager/scenarioatomics/atomic_criteria.py @@ -51,7 +51,7 @@ def __init__(self, actor, optional=False, terminate_on_failure=False): - super(Criterion, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self.name = name @@ -99,7 +99,7 @@ def __init__(self, actor, max_velocity, optional=False, name="CheckMaximumVeloci """ Setup actor and maximum allowed velovity """ - super(MaxVelocityTest, self).__init__(name, actor, optional) + super().__init__(name, actor, optional) self.success_value = max_velocity def update(self): @@ -145,14 +145,14 @@ def __init__(self, actor, distance, acceptable_distance=None, optional=False, na """ Setup actor """ - super(DrivenDistanceTest, self).__init__(name, actor, optional) + super().__init__(name, actor, optional) self.success_value = distance self.acceptable_value = acceptable_distance self._last_location = None def initialise(self): self._last_location = CarlaDataProvider.get_location(self.actor) - super(DrivenDistanceTest, self).initialise() + super().initialise() def update(self): """ @@ -197,7 +197,7 @@ def terminate(self, new_status): if self.test_status != "SUCCESS": self.test_status = "FAILURE" self.actual_value = round(self.actual_value, 2) - super(DrivenDistanceTest, self).terminate(new_status) + super().terminate(new_status) class AverageVelocityTest(Criterion): @@ -219,7 +219,7 @@ def __init__(self, actor, velocity, acceptable_velocity=None, optional=False, """ Setup actor and average velovity expected """ - super(AverageVelocityTest, self).__init__(name, actor, optional) + super().__init__(name, actor, optional) self.success_value = velocity self.acceptable_value = acceptable_velocity self._last_location = None @@ -227,7 +227,7 @@ def __init__(self, actor, velocity, acceptable_velocity=None, optional=False, def initialise(self): self._last_location = CarlaDataProvider.get_location(self.actor) - super(AverageVelocityTest, self).initialise() + super().initialise() def update(self): """ @@ -275,7 +275,7 @@ def terminate(self, new_status): """ if self.test_status == "RUNNING": self.test_status = "FAILURE" - super(AverageVelocityTest, self).terminate(new_status) + super().terminate(new_status) class CollisionTest(Criterion): @@ -301,7 +301,7 @@ def __init__(self, actor, other_actor=None, other_actor_type=None, """ Construction with sensor setup """ - super(CollisionTest, self).__init__(name, actor, optional, terminate_on_failure) + super().__init__(name, actor, optional, terminate_on_failure) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._other_actor = other_actor self._other_actor_type = other_actor_type @@ -318,8 +318,8 @@ def initialise(self): world = CarlaDataProvider.get_world() blueprint = world.get_blueprint_library().find('sensor.other.collision') self._collision_sensor = world.spawn_actor(blueprint, carla.Transform(), attach_to=self.actor) - self._collision_sensor.listen(lambda event: self._count_collisions(event)) - super(CollisionTest, self).initialise() + self._collision_sensor.listen(lambda event: self._count_collisions(event)) # pylint: disable=unnecessary-lambda + super().initialise() def update(self): """ @@ -354,7 +354,7 @@ def terminate(self, new_status): self._collision_sensor.stop() self._collision_sensor.destroy() self._collision_sensor = None - super(CollisionTest, self).terminate(new_status) + super().terminate(new_status) def _count_collisions(self, event): # pylint: disable=too-many-return-statements """Update collision count""" @@ -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: @@ -489,12 +489,12 @@ def __init__(self, actor, optional=False, name="CheckKeepLane"): """ Construction with sensor setup """ - super(KeepLaneTest, self).__init__(name, actor, optional) + super().__init__(name, actor, optional) world = self.actor.get_world() blueprint = world.get_blueprint_library().find('sensor.other.lane_invasion') self._lane_sensor = world.spawn_actor(blueprint, carla.Transform(), attach_to=self.actor) - self._lane_sensor.listen(lambda event: self._count_lane_invasion(event)) + self._lane_sensor.listen(lambda event: self._count_lane_invasion(event)) # pylint: disable=unnecessary-lambda def update(self): """ @@ -521,7 +521,7 @@ def terminate(self, new_status): if self._lane_sensor is not None: self._lane_sensor.destroy() self._lane_sensor = None - super(KeepLaneTest, self).terminate(new_status) + super().terminate(new_status) def _count_lane_invasion(self, event): """ @@ -546,7 +546,7 @@ def __init__(self, actor, min_x, max_x, min_y, max_y, name="ReachedRegionTest"): Setup trigger region (rectangle provided by [min_x,min_y] and [max_x,max_y] """ - super(ReachedRegionTest, self).__init__(name, actor) + super().__init__(name, actor) self._min_x = min_x self._max_x = max_x self._min_y = min_y @@ -598,7 +598,7 @@ def __init__(self, actor, duration=0, optional=False, terminate_on_failure=False """ Setup of the variables """ - super(OffRoadTest, self).__init__(name, actor, optional, terminate_on_failure) + super().__init__(name, actor, optional, terminate_on_failure) self._map = CarlaDataProvider.get_map() self._offroad = False @@ -676,7 +676,7 @@ def __init__(self, actor, duration=0, optional=False, terminate_on_failure=False """ Setup of the variables """ - super(EndofRoadTest, self).__init__(name, actor, optional, terminate_on_failure) + super().__init__(name, actor, optional, terminate_on_failure) self._map = CarlaDataProvider.get_map() self._end_of_road = False @@ -704,9 +704,8 @@ def update(self): if self._road_id is None: self._road_id = current_waypoint.road_id - else: - # Wait until the actor has left the road - if self._road_id != current_waypoint.road_id or self._start_time: + # Wait until the actor has left the road + elif self._road_id != current_waypoint.road_id or self._start_time: # Start counting if self._start_time is None: @@ -744,7 +743,7 @@ def __init__(self, actor, duration=0, optional=False, terminate_on_failure=False """ Construction with sensor setup """ - super(OnSidewalkTest, self).__init__(name, actor, optional, terminate_on_failure) + super().__init__(name, actor, optional, terminate_on_failure) self._map = CarlaDataProvider.get_map() self._onsidewalk_active = False @@ -892,7 +891,10 @@ 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 +909,10 @@ 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 +935,10 @@ 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 +953,10 @@ 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( @@ -955,7 +966,7 @@ def terminate(self, new_status): self._wrong_outside_lane_distance = 0 self.events.append(outsidelane_event) - super(OnSidewalkTest, self).terminate(new_status) + super().terminate(new_status) def _set_event_message(self, event, location, distance): """ @@ -1002,7 +1013,7 @@ def __init__(self, actor, route, optional=False, name="OutsideRouteLanesTest"): """ Constructor """ - super(OutsideRouteLanesTest, self).__init__(name, actor, optional) + super().__init__(name, actor, optional) self.units = "%" self._route = route @@ -1084,7 +1095,10 @@ 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 @@ -1182,7 +1196,7 @@ def __init__(self, actor, optional=False, name="WrongLaneTest"): """ Construction with sensor setup """ - super(WrongLaneTest, self).__init__(name, actor, optional) + super().__init__(name, actor, optional) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._map = CarlaDataProvider.get_map() @@ -1309,7 +1323,7 @@ def terminate(self, new_status): self._in_lane = True self.events.append(wrong_way_event) - super(WrongLaneTest, self).terminate(new_status) + super().terminate(new_status) def _set_event_message(self, event, location, distance, road_id, lane_id): """ @@ -1350,7 +1364,7 @@ class InRadiusRegionTest(Criterion): def __init__(self, actor, x, y, radius, name="InRadiusRegionTest"): """ """ - super(InRadiusRegionTest, self).__init__(name, actor) + super().__init__(name, actor) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._x = x # pylint: disable=invalid-name self._y = y # pylint: disable=invalid-name @@ -1369,7 +1383,10 @@ 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" @@ -1403,7 +1420,7 @@ class InRouteTest(Criterion): def __init__(self, actor, route, offroad_min=None, offroad_max=30, name="InRouteTest", terminate_on_failure=False): """ """ - super(InRouteTest, self).__init__(name, actor, terminate_on_failure=terminate_on_failure) + super().__init__(name, actor, terminate_on_failure=terminate_on_failure) self.units = None # We care about whether or not it fails, no units attached self._route = route @@ -1491,7 +1508,10 @@ 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), @@ -1529,7 +1549,7 @@ class RouteCompletionTest(Criterion): def __init__(self, actor, route, name="RouteCompletionTest", terminate_on_failure=False): """ """ - super(RouteCompletionTest, self).__init__(name, actor, terminate_on_failure=terminate_on_failure) + super().__init__(name, actor, terminate_on_failure=terminate_on_failure) self.units = "%" self.success_value = 100 self._route = route @@ -1614,7 +1634,7 @@ def terminate(self, new_status): if self.test_status == "INIT": self.test_status = "FAILURE" - super(RouteCompletionTest, self).terminate(new_status) + super().terminate(new_status) class RunningRedLightTest(Criterion): @@ -1632,7 +1652,7 @@ def __init__(self, actor, name="RunningRedLightTest", terminate_on_failure=False """ Init """ - super(RunningRedLightTest, self).__init__(name, actor, terminate_on_failure=terminate_on_failure) + super().__init__(name, actor, terminate_on_failure=terminate_on_failure) self._world = CarlaDataProvider.get_world() self._map = CarlaDataProvider.get_map() self._list_traffic_lights = [] @@ -1728,7 +1748,10 @@ 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, @@ -1812,7 +1835,7 @@ class RunningStopTest(Criterion): def __init__(self, actor, name="RunningStopTest", terminate_on_failure=False): """ """ - super(RunningStopTest, self).__init__(name, actor, terminate_on_failure=terminate_on_failure) + super().__init__(name, actor, terminate_on_failure=terminate_on_failure) self._world = CarlaDataProvider.get_world() self._map = CarlaDataProvider.get_map() self._list_stop_signs = [] @@ -1929,7 +1952,10 @@ 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, diff --git a/srunner/scenariomanager/scenarioatomics/atomic_trigger_conditions.py b/srunner/scenariomanager/scenarioatomics/atomic_trigger_conditions.py index ffa9f0f37..c39095dd4 100644 --- a/srunner/scenariomanager/scenarioatomics/atomic_trigger_conditions.py +++ b/srunner/scenariomanager/scenarioatomics/atomic_trigger_conditions.py @@ -53,7 +53,7 @@ def __init__(self, name): """ Default init. Has to be called via super from derived class """ - super(AtomicCondition, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self.name = name @@ -80,13 +80,13 @@ def terminate(self, new_status): class IfTriggerer(AtomicCondition): def __init__(self, actor_ego, actor_npc, comparison_operator=operator.gt, name="IfTriggerer"): - super(IfTriggerer, self).__init__(name) + super().__init__(name) self.actor_ego = actor_ego self.actor_npc = actor_npc self._comparison_operator = comparison_operator def initialise(self): - super(IfTriggerer, self).initialise() + super().initialise() def update(self): ego_speed_now = CarlaDataProvider.get_velocity(self.actor_ego) @@ -102,13 +102,13 @@ def update(self): class TimeOfWaitComparison(AtomicCondition): def __init__(self, duration_time, name="TimeOfWaitComparison"): - super(TimeOfWaitComparison, self).__init__(name) + super().__init__(name) self._duration_time = duration_time self._start_time = None def initialise(self): self._start_time = GameTime.get_time() - super(TimeOfWaitComparison, self).initialise() + super().initialise() def update(self): new_status = py_trees.common.Status.RUNNING @@ -124,7 +124,7 @@ def __init__(self, reference_actor, actor, distance, comparison_operator=operato """ Setup trigger distance """ - super(InTriggerNearCollision, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % self.__class__.__name__) self._reference_actor = reference_actor self._actor = actor @@ -176,7 +176,7 @@ def __init__(self, actor, osc_position, distance, along_route=False, """ Setup parameters """ - super(InTriggerDistanceToOSCPosition, self).__init__(name) + super().__init__(name) self._actor = actor self._osc_position = osc_position self._distance = distance @@ -241,7 +241,7 @@ def __init__(self, actor, osc_position, time, along_route=False, """ Setup parameters """ - super(InTimeToArrivalToOSCPosition, self).__init__(name) + super().__init__(name) self._map = CarlaDataProvider.get_map() self._actor = actor self._osc_position = osc_position @@ -316,7 +316,7 @@ def __init__(self, actor, name, duration=float("inf")): """ Setup actor """ - super(StandStill, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor @@ -328,7 +328,7 @@ def initialise(self): Initialize the start time of this condition """ self._start_time = GameTime.get_time() - super(StandStill, self).initialise() + super().initialise() def update(self): """ @@ -369,7 +369,7 @@ def __init__(self, actor, other_actor, speed, comparison_operator=operator.gt, """ Setup the parameters """ - super(RelativeVelocityToOtherActor, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._other_actor = other_actor @@ -417,7 +417,7 @@ def __init__(self, actor, target_velocity, comparison_operator=operator.gt, name """ Setup the atomic parameters """ - super(TriggerVelocity, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._target_velocity = target_velocity @@ -461,7 +461,7 @@ def __init__(self, actor, target_acceleration, comparison_operator=operator.gt, """ Setup trigger acceleration """ - super(TriggerAcceleration, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._target_acceleration = target_acceleration @@ -507,7 +507,7 @@ class TimeOfDayComparison(AtomicCondition): def __init__(self, dattime, comparison_operator=operator.gt, name="TimeOfDayComparison"): """ """ - super(TimeOfDayComparison, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._datetime = datetime.datetime.strptime(dattime, "%Y-%m-%dT%H:%M:%S") self._comparison_operator = comparison_operator @@ -553,7 +553,7 @@ def __init__(self, element_type, element_name, rule, name="OSCStartEndCondition" """ Setup element details """ - super(OSCStartEndCondition, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._element_type = element_type.upper() self._element_name = element_name @@ -566,7 +566,7 @@ def initialise(self): Initialize the start time of this condition """ self._start_time = GameTime.get_time() - super(OSCStartEndCondition, self).initialise() + super().initialise() def update(self): """ @@ -603,7 +603,7 @@ def __init__(self, actor, min_x, max_x, min_y, max_y, name="TriggerRegion"): Setup trigger region (rectangle provided by [min_x,min_y] and [max_x,max_y] """ - super(InTriggerRegion, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._min_x = min_x @@ -655,7 +655,7 @@ def __init__(self, reference_actor, actor, distance, comparison_operator=operato """ Setup trigger distance """ - super(InTriggerDistanceToVehicle, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._reference_actor = reference_actor self._actor = actor @@ -716,7 +716,7 @@ def __init__(self, """ Setup trigger distance """ - super(InTriggerDistanceToLocation, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._target_location = target_location self._actor = actor @@ -762,7 +762,7 @@ def __init__(self, actor, distance, name="InTriggerDistanceToNextIntersection"): """ Setup trigger distance """ - super(InTriggerDistanceToNextIntersection, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._distance = distance @@ -812,7 +812,7 @@ def __init__(self, actor, route, location, distance, name="InTriggerDistanceToLo """ Setup class members """ - super(InTriggerDistanceToLocationAlongRoute, self).__init__(name) + super().__init__(name) self._map = CarlaDataProvider.get_map() self._actor = actor self._location = location @@ -863,7 +863,7 @@ def __init__(self, actor, time, location, comparison_operator=operator.lt, name= """ Setup parameters """ - super(InTimeToArrivalToLocation, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._time = time @@ -919,7 +919,7 @@ def __init__(self, actor, other_actor, time, condition_freespace=False, """ Setup parameters """ - super(InTimeToArrivalToVehicle, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._map = CarlaDataProvider.get_map() self._actor = actor @@ -1025,11 +1025,11 @@ def __init__(self, actor, other_actor, time, side_lane, elif self._side_lane == 'left': other_side_waypoint = other_waypoint.get_right_lane() else: - raise Exception("cut_in_lane must be either 'left' or 'right'") + raise ValueError("cut_in_lane must be either 'left' or 'right'") other_side_location = other_side_waypoint.transform.location - super(InTimeToArrivalToVehicleSideLane, self).__init__( + super().__init__( actor, time, other_side_location, comparison_operator, name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) @@ -1047,7 +1047,7 @@ def update(self): elif self._side_lane == 'left': other_side_waypoint = other_waypoint.get_right_lane() else: - raise Exception("cut_in_lane must be either 'left' or 'right'") + raise ValueError("cut_in_lane must be either 'left' or 'right'") if other_side_waypoint is None: return new_status @@ -1056,7 +1056,7 @@ def update(self): if self._target_location is None: return new_status - new_status = super(InTimeToArrivalToVehicleSideLane, self).update() + new_status = super().update() return new_status @@ -1078,7 +1078,7 @@ def __init__(self, actor, other_actor, factor=1, check_distance=True, name="Wait """ Init """ - super(WaitUntilInFront, self).__init__(name) + super().__init__(name) self._actor = actor self._other_actor = other_actor self._distance = 10 @@ -1177,10 +1177,10 @@ def update(self): in_front = actor_dir.dot(self._ref_vector) > 0.0 # Is the actor close-by? - if not self._check_distance or location.distance(self._ref_location) < self._distance: - close_by = True - else: - close_by = False + close_by = ( + not self._check_distance + or location.distance(self._ref_location) < self._distance + ) if in_front and close_by: new_status = py_trees.common.Status.SUCCESS @@ -1204,7 +1204,7 @@ def __init__(self, actor, distance, name="DriveDistance"): """ Setup parameters """ - super(DriveDistance, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._target_distance = distance self._distance = 0 @@ -1213,7 +1213,7 @@ def __init__(self, actor, distance, name="DriveDistance"): def initialise(self): self._location = CarlaDataProvider.get_location(self._actor) - super(DriveDistance, self).initialise() + super().initialise() def update(self): """ @@ -1250,7 +1250,7 @@ def __init__(self, actor, name="AtRightmostLane"): """ Setup parameters """ - super(AtRightmostLane, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor self._map = CarlaDataProvider.get_map() @@ -1294,7 +1294,7 @@ def __init__(self, actor, state, name="WaitForTrafficLightState"): """ Setup traffic_light """ - super(WaitForTrafficLightState, self).__init__(name) + super().__init__(name) self.logger.debug("%s.__init__()" % (self.__class__.__name__)) self._actor = actor if "traffic_light" in actor.type_id else None self._state = state @@ -1334,7 +1334,7 @@ def __init__(self, traffic_signal_id, state, duration, delay=None, ref_id=None, """ Init """ - super(WaitForTrafficLightControllerState, self).__init__(name) + super().__init__(name) self.actor_id = traffic_signal_id self._actor = None self._start_time = None @@ -1362,6 +1362,7 @@ def initialise(self): self.duration_time = self.timeout else: return py_trees.common.Status.FAILURE + return None def update(self): """ @@ -1392,7 +1393,7 @@ class WaitEndIntersection(AtomicCondition): """ def __init__(self, actor, junction_id=None, debug=False, name="WaitEndIntersection"): - super(WaitEndIntersection, self).__init__(name) + super().__init__(name) self.actor = actor self.debug = debug self._junction_id = junction_id @@ -1434,7 +1435,7 @@ class WaitForBlackboardVariable(AtomicCondition): def __init__(self, variable_name, variable_value, var_init_value=None, debug=False, name="WaitForBlackboardVariable"): - super(WaitForBlackboardVariable, self).__init__(name) + super().__init__(name) self._debug = debug self._variable_name = variable_name self._variable_value = variable_value @@ -1465,7 +1466,7 @@ class CheckParameter(AtomicCondition): """ def __init__(self, parameter_ref, value, comparison_operator, debug=False, name="CheckParameter"): - super(CheckParameter, self).__init__(name) + super().__init__(name) self._parameter_ref = parameter_ref self._value = value self._comparison_operator = comparison_operator diff --git a/srunner/scenarios/actor_flow.py b/srunner/scenarios/actor_flow.py index 88a461f2c..491612276 100644 --- a/srunner/scenarios/actor_flow.py +++ b/srunner/scenarios/actor_flow.py @@ -109,10 +109,24 @@ 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(ActorFlow( - source_wp, sink_wp, self._source_dist_interval, self._sink_distance, - self._flow_speed, initial_actors=True, initial_junction=True)) + 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, + ) + ) root.add_child(ScenarioTimeout(self._scenario_timeout, self.config.name)) sequence = py_trees.composites.Sequence() @@ -179,7 +193,13 @@ 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) @@ -232,9 +252,10 @@ class HighwayExit(BasicScenario): This scenario is similar to CrossActorFlow It will remove the BackgroundActivity from the lane where ActorFlow starts. Then vehicles (cars) will start driving from start_actor_flow location to end_actor_flow location - in a relatively high speed, forcing the ego to accelerate to cut in the actor flow + in a relatively high speed, forcing the ego to accelerate to cut in the actor flow then exit from the highway. - This scenario works when Background Activity is running in route mode. And there should be no junctions in front of the ego. + This scenario works when Background Activity is running in route mode. + And there should be no junctions in front of the ego. """ def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, @@ -365,7 +386,11 @@ 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)) @@ -417,7 +442,7 @@ def __del__(self): class MergerIntoSlowTrafficV2(MergerIntoSlowTraffic): """ - Variation of MergerIntoSlowTraffic + Variation of MergerIntoSlowTraffic """ def _create_behavior(self): @@ -435,7 +460,13 @@ 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) @@ -667,7 +698,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) diff --git a/srunner/scenarios/background_activity.py b/srunner/scenarios/background_activity.py index fdacf5663..daf0a44a3 100644 --- a/srunner/scenarios/background_activity.py +++ b/srunner/scenarios/background_activity.py @@ -145,7 +145,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 = [] @@ -156,11 +156,7 @@ def contains_wp(self, wp): if not wp.is_junction: return False other_id = wp.get_junction().id - for junction in self.junctions: - if other_id == junction.id: - return True - return False - + return any(other_id == junction.id for junction in self.junctions) class BackgroundBehavior(AtomicBehavior): """ @@ -375,7 +371,7 @@ def _get_junctions_data(self): start_index = 0 # Ignore the junction the ego spawns at - for i in range(0, self._route_length - 1): + for i in range(self._route_length - 1): if not self._is_junction(self._route[i]): start_index = i break @@ -550,8 +546,8 @@ def _join_complex_junctions(self, filtered_data): # Get the complex index current_index = -1 - for i, complex_junctions in enumerate(complex_junctions): - complex_ids = [j.id for j in complex_junctions] + for i, complex_junction in enumerate(complex_junctions): + complex_ids = [j.id for j in complex_junction] if junction.id in complex_ids: current_index = i break @@ -1021,6 +1017,7 @@ def _add_incoming_actors(self, junction, source): self._add_actor_dict_element(junction.actor_dict, actor, at_oppo_entry_lane=at_oppo_entry_lane) return actor + return None def _move_road_sources(self, prev_ego_index): """ @@ -1031,7 +1028,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 @@ -1160,7 +1157,7 @@ def _initialise_opposite_sources(self): All opposite lanes have actor sources that will continually create vehicles, creating the sensation of permanent traffic. The actor spawning will be done later on (_update_opposite_sources). These sources are at a (somewhat) fixed distance - from the ego, but they never entering junctions. + from the ego, but they never entering junctions. """ self._opposite_route_index = None if not self._junctions: @@ -1301,8 +1298,20 @@ def _update_junction_sources(self): actor_dict = junction.actor_dict 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_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, + ) entry_lane_key = get_lane_key(source.entry_lane_wp) at_oppo_entry_lane = entry_lane_key in junction.opposite_entry_keys @@ -1331,7 +1340,11 @@ def _update_junction_sources(self): actor = self._spawn_source_actor(source, self._junction_spawn_dist) if not actor: continue - if junction.stop_non_route_entries and get_lane_key(source.entry_lane_wp) not in junction.route_entry_keys: + if ( + junction.stop_non_route_entries + and get_lane_key(source.entry_lane_wp) + not in junction.route_entry_keys + ): self._actors_speed_perc[actor] = 0 self._add_actor_dict_element(actor_dict, actor, at_oppo_entry_lane=at_oppo_entry_lane) source.actors.append(actor) @@ -1431,14 +1444,18 @@ 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): @@ -1829,8 +1846,7 @@ def _leave_space_in_front(self, space): front_actors.append(actor) distance = location.distance(self._ego_wp.transform.location) - if distance < min_distance: - min_distance = distance + min_distance = min(distance, min_distance) step = space - min_distance if step > 0: # Only move them if needed and only the minimum required distance @@ -1887,7 +1903,7 @@ def _readd_road_lane(self, lane_offset): for _ in range(abs(lane_offset)): side_wp = side_wp.get_right_lane() if lane_offset > 0 else side_wp.get_left_lane() if not side_wp: - print(f"WARNING: Couldn't find a lane with the desired offset") + print("WARNING: Couldn't find a lane with the desired offset") return add_lane_wp = side_wp @@ -2187,9 +2203,8 @@ def _is_location_behind_ego(self, location): ego_transform = self._route[self._route_index].transform ego_heading = ego_transform.get_forward_vector() ego_actor_vec = location - ego_transform.location - if ego_heading.dot(ego_actor_vec) < - 0.17: # 100º - return True - return False + return ego_heading.dot(ego_actor_vec) < - 0.17 # 100º + def _update_road_actors(self): """ @@ -2306,10 +2321,7 @@ def is_remapping_needed(current_wp, prev_wp): # Some roads have starting / ending lanes in the middle. Remap if that is detected prev_wps = get_same_dir_lanes(prev_wp) current_wps = get_same_dir_lanes(current_wp) - if len(prev_wps) != len(current_wps): - return True - - return False + return len(prev_wps) != len(current_wps) def is_road_dict_unchanging(wp_pairs): """Sometimes 'monitor_topology_changes' has already done the necessary changes""" @@ -2317,10 +2329,7 @@ def is_road_dict_unchanging(wp_pairs): if len(wp_pairs) != len(road_dict_keys): return False - for _, new_wp in wp_pairs: - if get_lane_key(new_wp) not in road_dict_keys: - return False - return True + return all(get_lane_key(new_wp) in road_dict_keys for _, new_wp in wp_pairs) if prev_route_index == self._route_index: return @@ -2349,7 +2358,14 @@ 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): @@ -2462,7 +2478,6 @@ def _update_junction_actors(self): # Set them ready to move so that the ego can smoothly cross the junction elif state == JUNCTION_EXIT_ROAD: self._set_road_actor_speed(location, actor, multiplier=1.5) - pass # Wait elif state == JUNCTION_EXIT_INACTIVE: diff --git a/srunner/scenarios/background_activity_parametrizer.py b/srunner/scenarios/background_activity_parametrizer.py index f11b8e7b7..0d1c3dcae 100644 --- a/srunner/scenarios/background_activity_parametrizer.py +++ b/srunner/scenarios/background_activity_parametrizer.py @@ -66,9 +66,19 @@ def _create_behavior(self): """ sequence = py_trees.composites.Sequence() - sequence.add_child(ChangeRoadBehavior(self._num_front_vehicles, self._num_back_vehicles, self._road_spawn_dist)) - sequence.add_child(ChangeJunctionBehavior( - self._junction_source_dist, self._junction_max_actors, self._junction_spawn_dist, self._junction_source_perc)) + sequence.add_child( + ChangeRoadBehavior( + self._num_front_vehicles, self._num_back_vehicles, self._road_spawn_dist + ) + ) + sequence.add_child( + ChangeJunctionBehavior( + self._junction_source_dist, + self._junction_max_actors, + self._junction_spawn_dist, + self._junction_source_perc, + ) + ) sequence.add_child(ChangeOppositeBehavior( self._opposite_source_dist, self._opposite_spawn_dist, self._opposite_active)) 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..98a96bfa6 100644 --- a/srunner/scenarios/construction_crash_vehicle.py +++ b/srunner/scenarios/construction_crash_vehicle.py @@ -226,7 +226,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,8 +271,17 @@ 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): + 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]) super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout) @@ -292,7 +301,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/cut_in_with_static_vehicle.py b/srunner/scenarios/cut_in_with_static_vehicle.py index 01d345bfd..a24b9782a 100644 --- a/srunner/scenarios/cut_in_with_static_vehicle.py +++ b/srunner/scenarios/cut_in_with_static_vehicle.py @@ -40,7 +40,16 @@ class StaticCutIn(BasicScenario): to cut in in front of the ego vehicle, forcing it to break """ - def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60): + def __init__( + self, + world, + ego_vehicles, + config, + randomize=False, + debug_mode=False, + criteria_enable=True, + timeout=60, + ): """ Setup all relevant parameters and create scenario """ @@ -159,8 +168,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) @@ -171,7 +180,7 @@ def _initialize_actors(self, config): blocker_wp = next_wps[0] # Spawn the vehicles in front of the cut in one - for i in range(self._front_vehicles): + for _ in range(self._front_vehicles): # Move to the side side_wp = blocker_wp.get_left_lane() if self._direction == 'left' else blocker_wp.get_right_lane() if not side_wp: diff --git a/srunner/scenarios/freeride.py b/srunner/scenarios/freeride.py index b300f3321..31d52a205 100644 --- a/srunner/scenarios/freeride.py +++ b/srunner/scenarios/freeride.py @@ -39,7 +39,7 @@ def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=Fals def _setup_scenario_trigger(self, config): """ """ - return None + return def _create_behavior(self): """ diff --git a/srunner/scenarios/invading_turn.py b/srunner/scenarios/invading_turn.py index cda71841e..4a68d5b57 100644 --- a/srunner/scenarios/invading_turn.py +++ b/srunner/scenarios/invading_turn.py @@ -6,8 +6,9 @@ # For a copy, see . """ -Scenario in which the ego is about to turn right -when a vehicle coming from the opposite lane invades the ego's lane, forcing the ego to move right to avoid a possible collision. +Scenario in which the ego is about to turn right +when a vehicle coming from the opposite lane invades the ego's lane, +forcing the ego to move right to avoid a possible collision. """ from __future__ import print_function @@ -47,8 +48,8 @@ def get_value_parameter(config, name, p_type, default): class InvadingTurn(BasicScenario): """ - This class holds everything required for a scenario in which the ego is about to turn right - when a vehicle coming from the opposite lane invades the ego's lane, + This class holds everything required for a scenario in which the ego is about to turn right + when a vehicle coming from the opposite lane invades the ego's lane, forcing the ego to move right to avoid a possible collision. This scenario is expected to take place on a road that has only one lane in each direction. @@ -152,7 +153,14 @@ 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/no_signal_junction_crossing.py b/srunner/scenarios/no_signal_junction_crossing.py index 0add82905..71513e6f6 100644 --- a/srunner/scenarios/no_signal_junction_crossing.py +++ b/srunner/scenarios/no_signal_junction_crossing.py @@ -21,7 +21,11 @@ KeepVelocity, StopVehicle) from srunner.scenariomanager.scenarioatomics.atomic_criteria import CollisionTest -from srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import InTriggerRegion, DriveDistance, WaitEndIntersection +from srunner.scenariomanager.scenarioatomics.atomic_trigger_conditions import ( + InTriggerRegion, + DriveDistance, + WaitEndIntersection, +) from srunner.scenarios.basic_scenario import BasicScenario diff --git a/srunner/scenarios/object_crash_vehicle.py b/srunner/scenarios/object_crash_vehicle.py index 485705ade..fc7eedc26 100644 --- a/srunner/scenarios/object_crash_vehicle.py +++ b/srunner/scenarios/object_crash_vehicle.py @@ -149,7 +149,16 @@ class DynamicObjectCrossing(BasicScenario): This is a single ego vehicle scenario """ - def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60): + def __init__( + self, + world, + ego_vehicles, + config, + randomize=False, + debug_mode=False, + criteria_enable=True, + timeout=60, + ): """ Setup all relevant parameters and create scenario """ @@ -388,7 +397,16 @@ class ParkingCrossingPedestrian(BasicScenario): This is a single ego vehicle scenario """ - def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60): + def __init__( + self, + world, + ego_vehicles, + config, + randomize=False, + debug_mode=False, + criteria_enable=True, + timeout=60, + ): """ Setup all relevant parameters and create scenario """ @@ -493,7 +511,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..1ba58df1c 100644 --- a/srunner/scenarios/open_scenario.py +++ b/srunner/scenarios/open_scenario.py @@ -17,8 +17,14 @@ import py_trees from srunner.scenariomanager.carla_data_provider import CarlaDataProvider -from srunner.scenariomanager.scenarioatomics.atomic_behaviors import ChangeWeather, ChangeRoadFriction, ChangeParameter, \ - ChangeActorLaneOffset, ChangeActorWaypoints, ChangeLateralDistance +from srunner.scenariomanager.scenarioatomics.atomic_behaviors import ( + ChangeWeather, + ChangeRoadFriction, + ChangeParameter, + ChangeActorLaneOffset, + ChangeActorWaypoints, + ChangeLateralDistance, +) from srunner.scenariomanager.scenarioatomics.atomic_behaviors import ChangeActorControl, ChangeActorTargetSpeed from srunner.scenariomanager.timer import GameTime from srunner.scenariomanager.weather_sim import OSCWeatherBehavior @@ -431,9 +437,9 @@ def _create_behavior(self): maneuver_behavior, "ACTION", child.attrib.get('name')) parallel_actions.add_child( oneshot_with_check(variable_name= # See note in get_xml_path - get_xml_path(story, sequence) + '>' + \ - get_xml_path(maneuver, child) + '>' + \ - str(actor_id), + get_xml_path(story, sequence) + '>' + + get_xml_path(maneuver, child) + '>' + + str(actor_id), behaviour=maneuver_behavior)) if child.tag == "StartTrigger": diff --git a/srunner/scenarios/osc2_scenario.py b/srunner/scenarios/osc2_scenario.py index 39f0fe83b..0e51c985c 100644 --- a/srunner/scenarios/osc2_scenario.py +++ b/srunner/scenarios/osc2_scenario.py @@ -227,7 +227,7 @@ def process_location_modifier(config, modifiers, duration: float, father_tree): print("END of change lane--") return # start - # Deal with absolute positioning vehicles first,such as lane(1, at: start) + # Deal with absolute positioning vehicles first, such as lane(1, at: start) event_start = [ m for m in modifiers @@ -244,9 +244,9 @@ def process_location_modifier(config, modifiers, duration: float, father_tree): car_config = config.get_car_config(car_name) car_config.set_arg({"init_transform": wp.transform}) - LOG_INFO( - f"{car_name} car init position will be set to {wp.transform.location}, roadid = {wp.road_id}, laneid={wp.lane_id}, s = {wp.s}" - ) + msg = (f"{car_name} car init position will be set to {wp.transform.location}, " + f"roadid = {wp.road_id}, laneid={wp.lane_id}, s = {wp.s}") + LOG_INFO(msg) else: raise RuntimeError(f"no valid position to spawn {car_name} car") @@ -303,9 +303,9 @@ def process_location_modifier(config, modifiers, duration: float, father_tree): car_config = config.get_car_config(npc_name) car_config.set_arg({"init_transform": init_wp.transform}) - LOG_WARNING( - f"{npc_name} car init position will be set to {init_wp.transform.location},roadid = {init_wp.road_id}, laneid={init_wp.lane_id}, s={init_wp.s}" - ) + msg = (f"{npc_name} car init position will be set to {init_wp.transform.location}, " + f"roadid = {init_wp.road_id}, laneid={init_wp.lane_id}, s={init_wp.s}") + LOG_WARNING(msg) # end end_group = [m for m in modifiers if m.get_trigger_point() == "end"] @@ -512,8 +512,8 @@ def visit_do_directive(self, node: ast_node.DoDirective): def bool_result(self, option): # wait(x < y) @drive_distance Handling of Boolean expressions x < y - expression_value = re.split("\W+", option) - symbol = re.search("\W+", option).group() + expression_value = re.split(r"\W+", option) + symbol = re.search(r"\W+", option).group() if symbol == "<": symbol = operator.lt elif symbol == ">": @@ -609,13 +609,12 @@ def visit_do_member(self, node: ast_node.DoMember): self.visit_call_directive(child) else: raise NotImplementedError(f"no implentment AST node {child}") + elif isinstance(sub_node, ast_node.DoMember): + self.visit_do_member(sub_node) else: - if isinstance(sub_node, ast_node.DoMember): - self.visit_do_member(sub_node) - else: - raise NotImplementedError("no supported ast node") + raise NotImplementedError("no supported ast node") - if re.match("\d", str(self.__duration)) and self.__duration != math.inf: + if re.match(r"\d", str(self.__duration)) and self.__duration != math.inf: self.father_ins.all_duration += int(self.__duration) def visit_wait_directive(self, node: ast_node.WaitDirective): @@ -696,7 +695,7 @@ def visit_behavior_invocation(self, node: ast_node.BehaviorInvocation): behavior_name = node.behavior_name behavior_invocation_name = None - if actor != None: + if actor is not None: behavior_invocation_name = actor + "." + behavior_name else: behavior_invocation_name = behavior_name @@ -712,7 +711,7 @@ def visit_behavior_invocation(self, node: ast_node.BehaviorInvocation): # scenario_declaration_node = self.father_ins.scenario_declaration.get(behavior_invocation_name) scenario_declaration_node_scope = scenario_declaration_node.get_scope() arguments = self.visit_children(node) - # Stores the value of the argument before the invoked scenario was overwritten, a: time=None + # Stores the value of the argument before the invoked scenario was overwritten, a: time=None # keyword_args = {} if isinstance(arguments, List): for arg in arguments: @@ -730,7 +729,7 @@ def visit_behavior_invocation(self, node: ast_node.BehaviorInvocation): # scope = scenario_declaration_node_scope.resolve(name) # scope.value = value del scenario_declaration_node - return + return None behavior = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, @@ -918,7 +917,7 @@ def visit_behavior_invocation(self, node: ast_node.BehaviorInvocation): actor_drive.add_child(car_driving) behavior.add_child(actor_drive) self.__cur_behavior.add_child(behavior) - return + return None process_location_modifier( self.father_ins.config, location_modifiers, self.__duration, actor_drive @@ -933,6 +932,7 @@ def visit_behavior_invocation(self, node: ast_node.BehaviorInvocation): behavior.add_child(actor_drive) self.__cur_behavior.add_child(behavior) + return None def visit_modifier_invocation(self, node: ast_node.ModifierInvocation): # actor = node.actor @@ -985,7 +985,7 @@ def visit_modifier_invocation(self, node: ast_node.ModifierInvocation): del method_declaration_node if method_value is not None: return method_value - return + return None else: pass arguments = self.visit_children(node) @@ -1194,10 +1194,10 @@ def visit_identifier_reference(self, node: ast_node.IdentifierReference): if isinstance(para_value, (Physical, float, int)): return para_value para_value = para_value.strip('"') - if re.fullmatch("(^[-]?[0-9]+(\.[0-9]+)?)\s*(\w+)", para_value): + if re.fullmatch(r"(^[-]?[0-9]+(\.[0-9]+)?)\s*(\w+)", para_value): # Regular expression ^[-]?[0-9]+(\.[0-9]+)? matching float # para_value_num = re.findall('^[-]?[0-9]+(\.[0-9]+)?', para_value)[0] - patter = re.compile("(^[-]?[0-9]+[\.[0-9]+]?)\s*(\w+)") + patter = re.compile(r"(^[-]?[0-9]+[\.[0-9]+]?)\s*(\w+)") para_value_num, para_value_unit = patter.match(para_value).groups() if para_value_num.count(".") == 1: return Physical( @@ -1267,10 +1267,10 @@ def visit_method_body(self, node: ast_node.MethodBody): exec_context = "" module_name = None for elem in external_list: - if "module" == elem[0]: + if elem[0] == "module": exec_context += "import " + str(elem[1]) + "\n" module_name = str(elem[1]) - elif "name" == elem[0]: + elif elem[0] == "name": exec_context += "ret = " if module_name is not None: exec_context += module_name + "." + str(elem[1]) + "(" @@ -1300,7 +1300,7 @@ def visit_method_body(self, node: ast_node.MethodBody): method_value = self.visit_binary_expression(child) if method_value is not None: return method_value - return + return None def visit_function_application_expression( self, node: ast_node.FunctionApplicationExpression @@ -1310,7 +1310,8 @@ def visit_function_application_expression( arguments = OSC2Helper.flat_list(self.visit_children(node)) line, column = node.get_loc() - # retrieval_name = para_type_str_sequence(config=self.father_ins.config, arguments=arguments, line=line, column=column, node=node) + # retrieval_name = para_type_str_sequence(config=self.father_ins.config, + # arguments=arguments, line=line, column=column, node=node) retrieval_name = arguments[0].split(".")[-1] method_scope = node.get_scope().resolve(retrieval_name) @@ -1345,8 +1346,7 @@ def visit_function_application_expression( if para_value is not None: return para_value return para_value - else: - pass + return None def visit_keep_constraint_declaration( self, node: ast_node.KeepConstraintDeclaration diff --git a/srunner/scenarios/parking_cut_in.py b/srunner/scenarios/parking_cut_in.py index 30c8fee63..916d6114e 100644 --- a/srunner/scenarios/parking_cut_in.py +++ b/srunner/scenarios/parking_cut_in.py @@ -30,7 +30,16 @@ class ParkingCutIn(BasicScenario): to cut in in front of the ego vehicle, forcing it to break """ - def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=False, criteria_enable=True, timeout=60): + def __init__( + self, + world, + ego_vehicles, + config, + randomize=False, + debug_mode=False, + criteria_enable=True, + timeout=60, + ): """ Setup all relevant parameters and create scenario """ @@ -81,7 +90,11 @@ def _initialize_actors(self, config): self.parking_slots.append(parking_wp.transform.location) self._blocker_actor = CarlaDataProvider.request_new_actor( - 'vehicle.*', parking_wp.transform, 'scenario no lights', attribute_filter={'base_type': 'car', 'generation': 2}) + "vehicle.*", + parking_wp.transform, + "scenario no lights", + attribute_filter={"base_type": "car", "generation": 2}, + ) if not self._blocker_actor: raise ValueError("Couldn't spawn the parked actor") self._blocker_actor.apply_control(carla.VehicleControl(hand_brake=True)) diff --git a/srunner/scenarios/parking_exit.py b/srunner/scenarios/parking_exit.py index acbb69643..0e4344a67 100644 --- a/srunner/scenarios/parking_exit.py +++ b/srunner/scenarios/parking_exit.py @@ -49,14 +49,19 @@ def get_value_parameter(config, name, p_type, default): class ParkingExit(BasicScenario): """ This class holds everything required for a scenario in which the ego would be teleported to the parking lane. - Once the scenario is triggered, the OutsideRouteLanesTest will be deactivated since the ego is out of the driving lane. + Once the scenario is triggered, the OutsideRouteLanesTest will be deactivated since the ego is out of the + driving lane. Then blocking vehicles will be generated in front of and behind the parking point. The ego need to exit from the parking lane and then merge into the driving lane. - After the ego is {end_distance} meters away from the parking point, the OutsideRouteLanesTest will be activated and the scenario ends. + After the ego is {end_distance} meters away from the parking point, + the OutsideRouteLanesTest will be activated and the scenario ends. - Note 1: For route mode, this shall be the first scenario of the route. The trigger point shall be the first point of the route waypoints. + Note: + For route mode, this shall be the first scenario of the route. + The trigger point shall be the first point of the route waypoints. - Note 2: Make sure there are enough space for spawning blocking vehicles. + Note: + Make sure there are enough space for spawning blocking vehicles. """ def __init__(self, world, ego_vehicles, config, debug_mode=False, criteria_enable=True, @@ -138,7 +143,11 @@ def _initialize_actors(self, config): self.parking_slots.append(behind_points[0].transform.location) actor_behind = CarlaDataProvider.request_new_actor( - 'vehicle.*', behind_points[0].transform, rolename='scenario no lights', attribute_filter=self._bp_attributes) + "vehicle.*", + behind_points[0].transform, + rolename="scenario no lights", + attribute_filter=self._bp_attributes, + ) if actor_behind is None: actor_front.destroy() raise ValueError("Couldn't spawn the vehicle behind the parking point") diff --git a/srunner/scenarios/pedestrian_crossing.py b/srunner/scenarios/pedestrian_crossing.py index 6cb70c2de..1c45c388e 100644 --- a/srunner/scenarios/pedestrian_crossing.py +++ b/srunner/scenarios/pedestrian_crossing.py @@ -126,7 +126,7 @@ def _initialize_actors(self, config): start_wp = wp # Spawn the walkers - for i, walker_data in enumerate(self._walker_data): + for _, walker_data in enumerate(self._walker_data): spawn_transform = self._get_walker_transform(start_wp, walker_data) walker = CarlaDataProvider.request_new_actor('walker.*', spawn_transform) if walker is None: @@ -240,7 +240,7 @@ def _setup_scenario_trigger(self, config): parallel = py_trees.composites.Parallel( policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE, name="ScenarioTrigger") - for i, walker in enumerate(reversed(self.other_actors)): + for _, walker in enumerate(reversed(self.other_actors)): parallel.add_child(MovePedestrianWithEgo(self.ego_vehicles[0], walker, 100)) parallel.add_child(trigger_tree) diff --git a/srunner/scenarios/route_obstacles.py b/srunner/scenarios/route_obstacles.py index 8a0a3dc11..bf6263490 100644 --- a/srunner/scenarios/route_obstacles.py +++ b/srunner/scenarios/route_obstacles.py @@ -65,7 +65,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 @@ -74,7 +74,11 @@ def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=Fals self._wait_duration = 5 self._offset = 0.6 - self._lights = carla.VehicleLightState.Special1 | carla.VehicleLightState.Special2 | carla.VehicleLightState.Position + self._lights = ( + carla.VehicleLightState.Special1 + | carla.VehicleLightState.Special2 + | carla.VehicleLightState.Position + ) self._distance = get_value_parameter(config, 'distance', float, 120) self._direction = get_value_parameter(config, 'direction', str, 'right') @@ -137,7 +141,11 @@ def _spawn_obstacle(self, wp, blueprint, accident_actor=False): spawn_transform.location += carla.Location(x=displacement * r_vec.x, y=displacement * r_vec.y, z=1) if accident_actor: actor = CarlaDataProvider.request_new_actor( - blueprint, spawn_transform, rolename='scenario no lights', attribute_filter={'base_type': 'car', 'generation': 2}) + blueprint, + spawn_transform, + rolename="scenario no lights", + attribute_filter={"base_type": "car", "generation": 2}, + ) else: actor = CarlaDataProvider.request_new_actor( blueprint, spawn_transform, rolename='scenario') @@ -238,8 +246,17 @@ 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): + 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]) super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout) @@ -302,7 +319,11 @@ def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=Fals self._wait_duration = 5 self._offset = 0.7 - self._lights = carla.VehicleLightState.RightBlinker | carla.VehicleLightState.LeftBlinker | carla.VehicleLightState.Position + self._lights = ( + carla.VehicleLightState.RightBlinker + | carla.VehicleLightState.LeftBlinker + | carla.VehicleLightState.Position + ) self._distance = get_value_parameter(config, 'distance', float, 120) self._direction = get_value_parameter(config, 'direction', str, 'right') @@ -364,7 +385,11 @@ def _spawn_obstacle(self, wp, blueprint): spawn_transform = wp.transform spawn_transform.location += carla.Location(x=displacement * r_vec.x, y=displacement * r_vec.y, z=1) actor = CarlaDataProvider.request_new_actor( - blueprint, spawn_transform, rolename='scenario no lights', attribute_filter={'base_type': 'car', 'generation': 2}) + blueprint, + spawn_transform, + rolename="scenario no lights", + attribute_filter={"base_type": "car", "generation": 2}, + ) if not actor: raise ValueError("Couldn't spawn an obstacle actor") @@ -443,8 +468,17 @@ 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): + 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]) super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout) @@ -613,7 +647,14 @@ 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,8 +700,17 @@ 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): + 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) super().__init__(world, ego_vehicles, config, randomize, debug_mode, criteria_enable, timeout) @@ -691,7 +741,14 @@ 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..edf8df565 100644 --- a/srunner/scenarios/route_scenario.py +++ b/srunner/scenarios/route_scenario.py @@ -71,7 +71,14 @@ 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 @@ -205,7 +212,15 @@ def get_all_scenario_classes(self): return all_scenario_classes - def _build_scenarios(self, world, ego_vehicle, scenario_definitions, scenarios_per_tick=5, timeout=300, debug=False): + def _build_scenarios( + self, + world, + ego_vehicle, + scenario_definitions, + scenarios_per_tick=5, + timeout=300, + debug=False, + ): """ Initializes the class of all the scenarios that will be present in the route. If a class fails to be initialized, a warning is printed but the route execution isn't stopped @@ -305,7 +320,14 @@ 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( @@ -330,7 +352,7 @@ def _create_weather_behavior(self): Create the weather behavior """ if len(self.config.weather) == 1: - return # Just set the weather at the beginning and done + return None# Just set the weather at the beginning and done return RouteWeatherBehavior(self.ego_vehicles[0], self.route, self.config.weather) def _create_lights_behavior(self): diff --git a/srunner/scenarios/vehicle_opens_door.py b/srunner/scenarios/vehicle_opens_door.py index 1f226e3b3..25388f7c3 100644 --- a/srunner/scenarios/vehicle_opens_door.py +++ b/srunner/scenarios/vehicle_opens_door.py @@ -30,7 +30,12 @@ WaitUntilInFrontPosition) from srunner.scenarios.basic_scenario import BasicScenario -from srunner.tools.background_manager import LeaveSpaceInFront, ChangeOppositeBehavior, StopBackVehicles, StartBackVehicles +from srunner.tools.background_manager import ( + LeaveSpaceInFront, + ChangeOppositeBehavior, + StopBackVehicles, + StartBackVehicles, +) def get_value_parameter(config, name, p_type, default): @@ -81,7 +86,14 @@ def __init__(self, world, ego_vehicles, config, randomize=False, debug_mode=Fals self._opposite_interval = get_interval_parameter(config, 'frequency', float, [20, 100]) - super().__init__("VehicleOpensDoorTwoWays", ego_vehicles, config, world, debug_mode, criteria_enable=criteria_enable) + super().__init__( + "VehicleOpensDoorTwoWays", + ego_vehicles, + config, + world, + debug_mode, + criteria_enable=criteria_enable, + ) def _get_displaced_location(self, actor, wp): """ @@ -119,7 +131,7 @@ def _initialize_actors(self, config): front_wps = starting_wp.next(self._parked_distance) if len(front_wps) == 0: raise ValueError("Couldn't find a spot to place the adversary vehicle") - elif len(front_wps) > 1: + if len(front_wps) > 1: print("WARNING: Found a diverging lane. Choosing one at random") self._front_wp = front_wps[0] @@ -148,7 +160,7 @@ def _initialize_actors(self, config): def _create_behavior(self): """ - Leave space in front, as the TM doesn't detect open doors, and change the opposite frequency + Leave space in front, as the TM doesn't detect open doors, and change the opposite frequency so that the ego can pass """ reference_wp = self._parked_wp.get_left_lane() diff --git a/srunner/scenarios/yield_to_emergency_vehicle.py b/srunner/scenarios/yield_to_emergency_vehicle.py index f77750e14..920ca1291 100644 --- a/srunner/scenarios/yield_to_emergency_vehicle.py +++ b/srunner/scenarios/yield_to_emergency_vehicle.py @@ -30,7 +30,7 @@ class YieldToEmergencyVehicle(BasicScenario): """ This class holds everything required for a scenario in which the ego has to yield its lane to emergency vehicle. - The background activity will be removed from the lane the emergency vehicle will pass through, + The background activity will be removed from the lane the emergency vehicle will pass through, and will be recreated once the scenario is over. Should be on the highway which is long enough and has no junctions. @@ -91,7 +91,10 @@ def _initialize_actors(self, config): self._ev_start_transform = ev_points[0].transform actor = CarlaDataProvider.request_new_actor( - "vehicle.*.*", self._ev_start_transform, attribute_filter={'special_type': 'emergency'}) + "vehicle.*.*", + self._ev_start_transform, + attribute_filter={"special_type": "emergency"}, + ) if actor is None: raise Exception("Couldn't spawn the emergency vehicle") @@ -111,7 +114,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 @@ -130,9 +133,13 @@ def _create_behavior(self): if self.route_mode: sequence.add_child(RemoveRoadLane(self._reference_waypoint)) - sequence.add_child(ActorTransformSetter(self.other_actors[0], self._ev_start_transform)) + sequence.add_child( + ActorTransformSetter(self.other_actors[0], self._ev_start_transform) + ) - main_behavior = py_trees.composites.Parallel(policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE) + main_behavior = py_trees.composites.Parallel( + policy=py_trees.common.ParallelPolicy.SUCCESS_ON_ONE + ) end_condition_1 = py_trees.composites.Sequence() end_condition_1.add_child(InTriggerDistanceToVehicle( @@ -140,14 +147,24 @@ def _create_behavior(self): end_condition_1.add_child(Idle(self._ev_idle_time)) end_condition_2 = py_trees.composites.Sequence() - end_condition_2.add_child(WaitUntilInFront(self.other_actors[0], self.ego_vehicles[0])) - end_condition_2.add_child(DriveDistance(self.other_actors[0], self._end_distance)) + end_condition_2.add_child( + WaitUntilInFront(self.other_actors[0], self.ego_vehicles[0]) + ) + end_condition_2.add_child( + DriveDistance(self.other_actors[0], self._end_distance) + ) main_behavior.add_child(end_condition_1) main_behavior.add_child(end_condition_2) - main_behavior.add_child(AdaptiveConstantVelocityAgentBehavior( - self.other_actors[0], self.ego_vehicles[0], speed_increment=self._speed_increment, opt_dict=self._opt_dict)) + main_behavior.add_child( + AdaptiveConstantVelocityAgentBehavior( + self.other_actors[0], + self.ego_vehicles[0], + speed_increment=self._speed_increment, + opt_dict=self._opt_dict, + ) + ) sequence.add_child(main_behavior) diff --git a/srunner/tests/carla_mocks/agents/navigation/behavior_agent.py b/srunner/tests/carla_mocks/agents/navigation/behavior_agent.py index 59c9f03cc..f5038bfc6 100644 --- a/srunner/tests/carla_mocks/agents/navigation/behavior_agent.py +++ b/srunner/tests/carla_mocks/agents/navigation/behavior_agent.py @@ -165,8 +165,14 @@ def _tailgating(self, waypoint, vehicle_list): behind_vehicle_state, behind_vehicle, _ = self._vehicle_obstacle_detected(vehicle_list, max( self._behavior.min_proximity_threshold, self._speed_limit / 2), up_angle_th=180, low_angle_th=160) if behind_vehicle_state and self._speed < get_speed(behind_vehicle): - if (right_turn == carla.LaneChange.Right or right_turn == - carla.LaneChange.Both) and waypoint.lane_id * right_wpt.lane_id > 0 and right_wpt.lane_type == carla.LaneType.Driving: + if ( + ( + right_turn == carla.LaneChange.Right + or right_turn == carla.LaneChange.Both + ) + and waypoint.lane_id * right_wpt.lane_id > 0 + and right_wpt.lane_type == carla.LaneType.Driving + ): new_vehicle_state, _, _ = self._vehicle_obstacle_detected(vehicle_list, max( self._behavior.min_proximity_threshold, self._speed_limit / 2), up_angle_th=180, lane_offset=1) if not new_vehicle_state: @@ -175,7 +181,11 @@ def _tailgating(self, waypoint, vehicle_list): self._behavior.tailgate_counter = 200 self.set_destination(end_waypoint.transform.location, right_wpt.transform.location) - elif left_turn == carla.LaneChange.Left and waypoint.lane_id * left_wpt.lane_id > 0 and left_wpt.lane_type == carla.LaneType.Driving: + elif ( + left_turn == carla.LaneChange.Left + and waypoint.lane_id * left_wpt.lane_id > 0 + and left_wpt.lane_type == carla.LaneType.Driving + ): new_vehicle_state, _, _ = self._vehicle_obstacle_detected(vehicle_list, max( self._behavior.min_proximity_threshold, self._speed_limit / 2), up_angle_th=180, lane_offset=-1) if not new_vehicle_state: 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..dfe46d011 100644 --- a/srunner/tests/carla_mocks/agents/navigation/global_route_planner.py +++ b/srunner/tests/carla_mocks/agents/navigation/global_route_planner.py @@ -72,10 +72,21 @@ 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: - destination_index = self._find_closest_in_list(destination_waypoint, path) + 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 diff --git a/srunner/tools/background_manager.py b/srunner/tools/background_manager.py index 436ff4262..c36881aee 100644 --- a/srunner/tools/background_manager.py +++ b/srunner/tools/background_manager.py @@ -26,7 +26,14 @@ class ChangeRoadBehavior(AtomicBehavior): switch_source (bool): (De)activatea the road sources. """ - def __init__(self, num_front_vehicles=None, num_back_vehicles=None, spawn_dist=None, extra_space=None, name="ChangeRoadBehavior"): + def __init__( + self, + num_front_vehicles=None, + num_back_vehicles=None, + spawn_dist=None, + extra_space=None, + name="ChangeRoadBehavior", + ): self._num_front = num_front_vehicles self._num_back = num_back_vehicles self._spawn_dist = spawn_dist @@ -35,7 +42,9 @@ def __init__(self, num_front_vehicles=None, num_back_vehicles=None, spawn_dist=N def update(self): py_trees.blackboard.Blackboard().set( - "BA_ChangeRoadBehavior", [self._num_front, self._num_back, self._spawn_dist, self._extra_space], overwrite=True + "BA_ChangeRoadBehavior", + [self._num_front, self._num_back, self._spawn_dist, self._extra_space], + overwrite=True, ) return py_trees.common.Status.SUCCESS @@ -73,7 +82,14 @@ class ChangeJunctionBehavior(AtomicBehavior): max_actors (int): Max amount of concurrent alive actors spawned by the same source. Can't be negative """ - def __init__(self, source_dist=None, spawn_dist=None, max_actors=None, source_perc=None, name="ChangeJunctionBehavior"): + def __init__( + self, + source_dist=None, + spawn_dist=None, + max_actors=None, + source_perc=None, + name="ChangeJunctionBehavior", + ): self._source_dist = source_dist self._spawn_dist = spawn_dist self._max_actors = max_actors @@ -82,7 +98,9 @@ def __init__(self, source_dist=None, spawn_dist=None, max_actors=None, source_pe def update(self): py_trees.blackboard.Blackboard().set( - "BA_ChangeJunctionBehavior", [self._source_dist, self._spawn_dist, self._max_actors, self._perc], overwrite=True + "BA_ChangeJunctionBehavior", + [self._source_dist, self._spawn_dist, self._max_actors, self._perc], + overwrite=True, ) return py_trees.common.Status.SUCCESS @@ -161,16 +179,18 @@ 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) def update(self): """Updates the blackboard and succeds""" - py_trees.blackboard.Blackboard().set("BA_LeaveSpaceInFront", [self._space], overwrite=True) + py_trees.blackboard.Blackboard().set( + "BA_LeaveSpaceInFront", self._space, overwrite=True + ) return py_trees.common.Status.SUCCESS - class SwitchRouteSources(AtomicBehavior): """ Updates the blackboard to tell the background activity to (de)activate all route sources @@ -222,20 +242,6 @@ def update(self): return py_trees.common.Status.SUCCESS -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) - - def update(self): - """Updates the blackboard and succeds""" - py_trees.blackboard.Blackboard().set("BA_LeaveSpaceInFront", self._space, overwrite=True) - return py_trees.common.Status.SUCCESS - class LeaveCrossingSpace(AtomicBehavior): """ @@ -257,7 +263,8 @@ class HandleJunctionScenario(AtomicBehavior): Args: clear_junction (bool): Remove all actors inside the junction, and all that enter it afterwards - clear_ego_entry (bool): Remove all actors part of the ego road to ensure a smooth entry of the ego to the junction. + clear_ego_entry (bool): Remove all actors part of the ego road + to ensure a smooth entry of the ego to the junction. remove_entries (list): list of waypoint representing a junction entry that needs to be removed remove_exits (list): list of waypoint representing a junction exit that needs to be removed stop_entries (bool): Stops all the junction entries diff --git a/srunner/tools/openscenario_parser.py b/srunner/tools/openscenario_parser.py index 4392db4f7..be8f9fe17 100644 --- a/srunner/tools/openscenario_parser.py +++ b/srunner/tools/openscenario_parser.py @@ -105,7 +105,10 @@ def is_literal(self) -> bool: """ Returns: True when text is a literal/number """ - return self._is_matching(pattern=r"(-)?\d+(\.\d*)?") or self._is_matching(pattern=r"[-+]?(\d+(\.\d*)?|\.\d+)([eE][-+]?\d+)?") + return ( + self._is_matching(pattern=r"(-)?\d+(\.\d*)?") + or self._is_matching(pattern=r"[-+]?(\d+(\.\d*)?|\.\d+)([eE][-+]?\d+)?") + ) def is_parameter(self) -> bool: """ @@ -221,6 +224,8 @@ def __isub__(self, other) -> bool: def __abs__(self): return abs(self.__float__()) + + # TODO: Should implement __hash__ class OpenScenarioParser(object): @@ -1516,11 +1521,10 @@ def convert_maneuver_to_atomic(action, actor, actor_list, catalogs, config): else: raise AttributeError("Unknown private action") + elif list(action): + raise AttributeError("Unknown action: {}".format(maneuver_name)) else: - if list(action): - raise AttributeError("Unknown action: {}".format(maneuver_name)) - else: - return Idle(duration=0, name=maneuver_name) + return Idle(duration=0, name=maneuver_name) return atomic diff --git a/srunner/tools/osc2_helper.py b/srunner/tools/osc2_helper.py index 33e4f5955..29c75d710 100644 --- a/srunner/tools/osc2_helper.py +++ b/srunner/tools/osc2_helper.py @@ -58,7 +58,8 @@ def gen_osc2_ast(cls, osc2_file_name: str): def vector_angle(v1: List[int], v2: List[int]) -> int: """Calculate the angle between vectors v1 and v2. Parameters: - v1: vector v1, list type [x1, y1, x2, y2], where x1.y1 represents the starting coordinates and x2, y2 represent the ending coordinates. + v1: vector v1, list type [x1, y1, x2, y2], + where x1.y1 represents the starting coordinates and x2, y2 represent the ending coordinates. v2: same as above. Return: the angle, positive for clockwise and negative for counterclockwise. """ diff --git a/srunner/tools/scenario_helper.py b/srunner/tools/scenario_helper.py index 4aa03b641..cd77eae72 100644 --- a/srunner/tools/scenario_helper.py +++ b/srunner/tools/scenario_helper.py @@ -270,7 +270,8 @@ def generate_target_waypoint_list(waypoint, turn=0): plan[-3][0].transform.location, plan[-2][0].transform.location) angle_wp = math.acos( - np.dot(v_1, v_2) / abs((np.linalg.norm(v_1) * np.linalg.norm(v_2)))) + np.dot(v_1, v_2) / abs(np.linalg.norm(v_1) * np.linalg.norm(v_2)) + ) if angle_wp < threshold: break elif reached_junction and not plan[-1][0].is_intersection: @@ -678,8 +679,7 @@ def get_troad_from_transform(actor_transform): 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 - else: - if c_wp.lane_id < 0: + elif c_wp.lane_id < 0: t_road = -1*t_road return t_road @@ -703,7 +703,7 @@ def get_distance_between_actors(current, target, distance_type="euclidianDistanc extent_sum_x = target.bounding_box.extent.x + current.bounding_box.extent.x extent_sum_y = target.bounding_box.extent.y + current.bounding_box.extent.y if distance_type == "longitudinal": - if not current_wp.road_id == target_wp.road_id: + if current_wp.road_id != target_wp.road_id: distance = 0 # Get the route route = global_planner.trace_route(current_transform.location, target_transform.location) diff --git a/tests/test-ast-listener.py b/tests/test-ast-listener.py index f55bfc9c1..4a9ae4aee 100644 --- a/tests/test-ast-listener.py +++ b/tests/test-ast-listener.py @@ -158,7 +158,7 @@ def main(input_stream): 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() diff --git a/tests/test-ast-visitor.py b/tests/test-ast-visitor.py index 81d06d895..38d7fd42a 100644 --- a/tests/test-ast-visitor.py +++ b/tests/test-ast-visitor.py @@ -180,7 +180,7 @@ def main(input_stream): 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() diff --git a/tests/test-ast.py b/tests/test-ast.py index c4cbe220a..a00a77659 100644 --- a/tests/test-ast.py +++ b/tests/test-ast.py @@ -89,7 +89,7 @@ def main(input_stream, output_name): 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() diff --git a/tests/test-symbol.py b/tests/test-symbol.py index 46684ff20..302e3f687 100644 --- a/tests/test-symbol.py +++ b/tests/test-symbol.py @@ -16,7 +16,6 @@ from srunner.osc2.ast_manager.ast_builder import ASTBuilder - def main(input_stream): quiet = False OscErrorListeners = OscErrorListener(input_stream) @@ -59,7 +58,7 @@ def main(input_stream): import_msg.clear_msg() 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()