def get_spawn_point( world: carla.World, # pylint: disable=no-member spawn_point: Optional[Union[int, carla.Transform]] # pylint: disable=no-member ) -> carla.Location: # pylint: disable=no-member """Parses and returns a CARLA spawn points.""" if isinstance(spawn_point, carla.Transform): # pylint: disable=no-member _spawn_point = spawn_point elif isinstance(spawn_point, int): _spawn_point = world.get_map().get_spawn_points()[spawn_point] else: _spawn_point = random.choice(world.get_map().get_spawn_points()) return _spawn_point
def __init__(self, carla_world: carla.World, lane_gt_config, debug=False): self.carla_world = carla_world self.map = carla_world.get_map() # carla.Transform of current query point self._carla_tform = None # Search radius self._radius = lane_gt_config['radius'] # bool: True to draw lane boundaries points during querying self.debug = debug self.gt = {} # Current waypoint self.waypoint = None # Flag indicating ego vehicle is in junction self.gt['in_junction'] = False # Current road id self.gt['road_id'] = None # Current lane id (to know the order of double marking types) self.gt['lane_id'] = None # Flag indicating ego vehicle is going into junction self.gt['into_junction'] = False # Carla.LaneMarking object of each marking self.gt['left_marking'] = None self.gt['next_left_marking'] = None self.gt['right_marking'] = None self.gt['next_right_marking'] = None # c0 and c1 of lane markings self.gt['left_marking_coeffs'] = [0, 0] self.gt['next_left_marking_coeffs'] = [0, 0] self.gt['right_marking_coeffs'] = [0, 0] self.gt['next_right_marking_coeffs'] = [0, 0]
def spawn_vehicles( world: carla.World, # pylint: disable=no-member num_vehicles: int, ) -> Sequence[carla.Vehicle]: # pylint: disable=no-member """Spawns `vehicles` randomly in spawn points. Args: world: The world object associated with the simulation. num_vehicles: The number of vehicles to spawn. Returns: The list of vehicles actors. """ # Blueprints library. bl = world.get_blueprint_library() # List of spawn points. spawn_points = world.get_map().get_spawn_points() # Output container actors = list() for _ in range(num_vehicles): # Fetch random blueprint. vehicle_bp = random.choice(bl.filter("vehicle.*")) # Attempt to spawn vehicle in random location. actor = world.try_spawn_actor(vehicle_bp, random.choice(spawn_points)) if actor is not None: # Enable autopilot. actor.set_autopilot(True) # Append actor to the list. actors.append(actor) logging.debug("Spawned {} other vehicles".format(len(actors))) return actors
def __init__(self, world: carla.World, route_resolution=1.0): """ Args: world (carla.World): the carla world instance route_resolution (float): the resolution in meters for planned route """ self._world = world self._map = world.get_map() self._waypoints = self._map.generate_waypoints(2.0) self._actors = [] # including vehicles and walkers self._actor_dict = {} self._actor_locations = {} self._route_resolution = route_resolution dao = GlobalRoutePlannerDAO(world.get_map(), sampling_resolution=route_resolution) self._global_route_planner = GlobalRoutePlanner(dao) self._global_route_planner.setup()
def __init__( self, world: carla.World, args, transform: carla.Transform, agent_type: str, render_image: bool, evaluation: bool): self.world = world self.map = world.get_map() self.vehicle = None self.agent = None self.camera_sensor_dict = None self.segment_sensor_dict = None self.collision_sensor = None self.args = args self.agent_type = agent_type self.render_image = render_image self.evaluation = evaluation self.image_width = args.width self.image_height = args.height self.camera_keywords: List[str] = args.camera_keywords set_world_rendering_option(self.world, self.render_image) self.data_frame_dict = dict() self.data_frame_number_ = None self.progress_index = 0 self.data_frame_buffer = set() self.stop_dict = dict() self.cmd_dict = dict() ExperimentDirectory.__init__(self, get_timestamp()) self.target_waypoint_ = None self.waypoint_dict = dict() self.waypoint_buffer = set() set_world_asynchronous(self.world) self.set_vehicle(transform) if self.autopilot: self.set_agent() self.export_meta() set_world_synchronous(self.world) if self.render_image: self.set_camera_sensor() self.set_segment_sensor() self.set_collision_sensor()
def get_pedestrians_surface( world: carla.World, # pylint: disable=no-member pixels_per_meter: int = 5, scale: float = 1.0, margin: int = 150, ) -> pygame.Surface: """Generates a `PyGame` surface of pedestrians. Args: world: The `CARLA` world. pixels_per_meter: The number of pixels rendered per meter. scale: The scaling factor of the rendered map. margin: The number of pixels used for margin. Returns The pedestrians rendered as a `PyGame` surface. """ # Fetch CARLA map. carla_map = world.get_map() # Fetch all the pedestrians. pedestrians = [ actor for actor in world.get_actors() if "walker.pedestrian" in actor.type_id ] # Setups the `PyGame` surface and offsets. world_offset, surface = draw_settings( carla_map=carla_map, pixels_per_meter=pixels_per_meter, scale=scale, margin=margin, ) # Set background black surface.fill(COLORS["BLACK"]) # Iterate over pedestrians. for pedestrian in pedestrians: # Draw pedestrian as a rectangular. corners = actor_to_corners(pedestrian) # Convert to pixel coordinates. corners = [ world_to_pixel(p, scale, world_offset, pixels_per_meter) for p in corners ] pygame.draw.polygon(surface, COLORS["WHITE"], corners) return surface
def global_plan( world: carla.World, # pylint: disable=no-member origin: carla.Location, # pylint: disable=no-member destination: carla.Location, # pylint: disable=no-member ) -> Tuple[Sequence[carla.Waypoint], Sequence[Any], float]: # pylint: disable=no-member """Generates the optimal plan between two location, respecting the topology. Args: world: The `CARLA` world. origin: The starting location. destination: The final destination. Returns: waypoints: A sequence of waypoints. roadoptions: A sequence of commands to navigate at each waypoint. distances: The distance per pair of waypoints of the plan. """ try: from agents.navigation.global_route_planner import GlobalRoutePlanner # pylint: disable=import-error from agents.navigation.global_route_planner_dao import GlobalRoutePlannerDAO # pylint: disable=import-error except ImportError: raise ImportError( "Missing CARLA installation, " "make sure the environment variable CARLA_ROOT is provided " "and that the PythonAPI is `easy_install`ed") # Setup global planner. grp_dao = GlobalRoutePlannerDAO(wmap=world.get_map(), sampling_resolution=1) grp = GlobalRoutePlanner(grp_dao) grp.setup() # Generate plan. waypoints, roadoptions = zip(*grp.trace_route(origin, destination)) # Accummulate pairwise distance. distances = [0.0] for i in range(1, len(waypoints)): loc_tm1 = waypoints[i - 1].transform.location loc_tm1 = np.asarray([loc_tm1.x, loc_tm1.y, loc_tm1.z]) loc_t = waypoints[i].transform.location loc_t = np.asarray([loc_t.x, loc_t.y, loc_t.z]) distances.append(np.linalg.norm(loc_tm1 - loc_t)) return waypoints, roadoptions, distances
def compute_all_paths_from_location( location: carla.Location, carla_world: carla.World, dist_between_waypoints: float, path_length: int = 10, lane_type: carla.LaneType = carla.LaneType.Driving, verbose: bool = False): paths = [] path_start = carla_world.get_map().get_waypoint(location, lane_type=lane_type) if verbose: print("Path start - ") print_waypoint_info(path_start) add_to_path(path_start, paths, [], 0, dist_between_waypoints, path_length, verbose) return paths
def get_traffic_lights_surface( world: carla.World, # pylint: disable=no-member pixels_per_meter: int = 5, scale: float = 1.0, margin: int = 150, ) -> Tuple[pygame.Surface, pygame.Surface, pygame.Surface]: """Generates three `PyGame` surfaces of traffic lights (Green, Yellow, Red). Args: world: The `CARLA` world. pixels_per_meter: The number of pixels rendered per meter. scale: The scaling factor of the rendered map. margin: The number of pixels used for margin. Returns The traffic lights rendered as `PyGame` surface (Green, Yellow, Red). """ # Fetch CARLA map. carla_map = world.get_map() # Fetch all the pedestrians. traffic_lights = [ actor for actor in world.get_actors() if "traffic.traffic_light" in actor.type_id ] # Setups the `PyGame` surface and offsets. world_offset, green_surface = draw_settings( carla_map=carla_map, pixels_per_meter=pixels_per_meter, scale=scale, margin=margin, ) width = green_surface.get_width() height = green_surface.get_height() yellow_surface = pygame.Surface((width, height)) # pylint: disable=too-many-function-args red_surface = pygame.Surface((width, height)) # pylint: disable=too-many-function-args # Set background black green_surface.fill(COLORS["BLACK"]) yellow_surface.fill(COLORS["BLACK"]) red_surface.fill(COLORS["BLACK"]) # Iterate over pedestrians. for traffic_light in traffic_lights: # Identify state of the traffic light. if traffic_light.state.name == "Green": surface = green_surface elif traffic_light.state.name == "Yellow": surface = yellow_surface elif traffic_light.state.name == "Red": surface = red_surface else: continue # Convert to pixel coordinates. center = world_to_pixel( traffic_light.get_transform().location, scale, world_offset, pixels_per_meter, ) pygame.draw.circle(surface, COLORS["WHITE"], center, 10) return green_surface, yellow_surface, red_surface
def get_lane_boundaries_surface( world: carla.World, # pylint: disable=no-member pixels_per_meter: int = 5, scale: float = 1.0, margin: int = 150, ) -> pygame.Surface: """Generates a `PyGame` surface of a CARLA town lane boundaries. Heavily inspired by the official CARLA `no_rendering_mode.py` example. Args: world: The `CARLA` world. pixels_per_meter: The number of pixels rendered per meter. scale: The scaling factor of the rendered map. margin: The number of pixels used for margin. Returns The lane boundaries of a CARLA town as a `PyGame` surface. """ # Fetch CARLA map. carla_map = world.get_map() # Setups the `PyGame` surface and offsets. world_offset, surface = draw_settings( carla_map=carla_map, pixels_per_meter=pixels_per_meter, scale=scale, margin=margin, ) def get_lane_markings(lane_marking_type, waypoints, sign): margin = 0.25 marking_1 = [ world_to_pixel( lateral_shift(w.transform, sign * w.lane_width * 0.5), scale, world_offset, pixels_per_meter, ) for w in waypoints ] if lane_marking_type == carla.LaneMarkingType.Broken or ( # pylint: disable=no-member lane_marking_type == carla.LaneMarkingType.Solid): # pylint: disable=no-member return [(lane_marking_type, marking_1)] else: marking_2 = [ world_to_pixel( lateral_shift(w.transform, sign * (w.lane_width * 0.5 + margin * 2)), scale, world_offset, pixels_per_meter, ) for w in waypoints ] if lane_marking_type == carla.LaneMarkingType.SolidBroken: # pylint: disable=no-member return [ (carla.LaneMarkingType.Broken, marking_1), # pylint: disable=no-member (carla.LaneMarkingType.Solid, marking_2), # pylint: disable=no-member ] elif lane_marking_type == carla.LaneMarkingType.BrokenSolid: # pylint: disable=no-member return [ (carla.LaneMarkingType.Solid, marking_1), # pylint: disable=no-member (carla.LaneMarkingType.Broken, marking_2), # pylint: disable=no-member ] elif lane_marking_type == carla.LaneMarkingType.BrokenBroken: # pylint: disable=no-member return [ (carla.LaneMarkingType.Broken, marking_1), # pylint: disable=no-member (carla.LaneMarkingType.Broken, marking_2), # pylint: disable=no-member ] elif lane_marking_type == carla.LaneMarkingType.SolidSolid: # pylint: disable=no-member return [ (carla.LaneMarkingType.Solid, marking_1), # pylint: disable=no-member (carla.LaneMarkingType.Solid, marking_2), # pylint: disable=no-member ] return [ (carla.LaneMarkingType.NONE, []), # pylint: disable=no-member ] def draw_solid_line(surface, color, closed, points, width): if len(points) >= 2: pygame.draw.lines(surface, color, closed, points, width) def draw_broken_line(surface, color, closed, points, width): broken_lines = [ x for n, x in enumerate(zip(*(iter(points), ) * 20)) if n % 3 == 0 ] for line in broken_lines: pygame.draw.lines(surface, color, closed, line, width) def draw_lane_marking_single_side(surface, waypoints, sign): lane_marking = None marking_type = carla.LaneMarkingType.NONE # pylint: disable=no-member previous_marking_type = carla.LaneMarkingType.NONE # pylint: disable=no-member markings_list = [] temp_waypoints = [] current_lane_marking = carla.LaneMarkingType.NONE # pylint: disable=no-member for sample in waypoints: lane_marking = sample.left_lane_marking if sign < 0 else sample.right_lane_marking if lane_marking is None: continue marking_type = lane_marking.type if current_lane_marking != marking_type: markings = get_lane_markings( previous_marking_type, temp_waypoints, sign, ) current_lane_marking = marking_type for marking in markings: markings_list.append(marking) temp_waypoints = temp_waypoints[-1:] else: temp_waypoints.append((sample)) previous_marking_type = marking_type # Add last marking. last_markings = get_lane_markings( previous_marking_type, temp_waypoints, sign, ) for marking in last_markings: markings_list.append(marking) for markings in markings_list: if markings[0] == carla.LaneMarkingType.Solid: # pylint: disable=no-member draw_solid_line( surface, COLORS["WHITE"], False, markings[1], 2, ) elif markings[0] == carla.LaneMarkingType.Broken: # pylint: disable=no-member draw_broken_line( surface, COLORS["WHITE"], False, markings[1], 2, ) # Set background black surface.fill(COLORS["BLACK"]) precision = 0.05 # Parse OpenDrive topology. topology = [x[0] for x in carla_map.get_topology()] topology = sorted(topology, key=lambda w: w.transform.location.z) set_waypoints = [] for waypoint in topology: waypoints = [waypoint] nxt = waypoint.next(precision) if len(nxt) > 0: nxt = nxt[0] while nxt.road_id == waypoint.road_id: waypoints.append(nxt) nxt = nxt.next(precision) if len(nxt) > 0: nxt = nxt[0] else: break set_waypoints.append(waypoints) # Draw roads. for waypoints in set_waypoints: waypoint = waypoints[0] road_left_side = [ lateral_shift(w.transform, -w.lane_width * 0.5) for w in waypoints ] road_right_side = [ lateral_shift(w.transform, w.lane_width * 0.5) for w in waypoints ] polygon = road_left_side + [x for x in reversed(road_right_side)] polygon = [ world_to_pixel( x, scale=scale, offset=world_offset, pixels_per_meter=pixels_per_meter, ) for x in polygon ] # Draw Lane Markings if not waypoint.is_junction: # Left Side draw_lane_marking_single_side(surface, waypoints, -1) # Right Side draw_lane_marking_single_side(surface, waypoints, 1) return surface
def get_road_surface( world: carla.World, # pylint: disable=no-member pixels_per_meter: int = 5, scale: float = 1.0, margin: int = 150, ) -> pygame.Surface: """Generates a `PyGame` surface of a CARLA town. Heavily inspired by the official CARLA `no_rendering_mode.py` example. Args: world: The `CARLA` world. pixels_per_meter: The number of pixels rendered per meter. scale: The scaling factor of the rendered map. margin: The number of pixels used for margin. Returns The topology of a CARLA town as a `PyGame` surface. """ # Fetch CARLA map. carla_map = world.get_map() # Setups the `PyGame` surface and offsets. world_offset, surface = draw_settings( carla_map=carla_map, pixels_per_meter=pixels_per_meter, scale=scale, margin=margin, ) # Set background black surface.fill(COLORS["BLACK"]) precision = 0.05 # Parse OpenDrive topology. topology = [x[0] for x in carla_map.get_topology()] topology = sorted(topology, key=lambda w: w.transform.location.z) set_waypoints = [] for waypoint in topology: waypoints = [waypoint] nxt = waypoint.next(precision) if len(nxt) > 0: nxt = nxt[0] while nxt.road_id == waypoint.road_id: waypoints.append(nxt) nxt = nxt.next(precision) if len(nxt) > 0: nxt = nxt[0] else: break set_waypoints.append(waypoints) # Draw roads. for waypoints in set_waypoints: waypoint = waypoints[0] road_left_side = [ lateral_shift(w.transform, -w.lane_width * 0.5) for w in waypoints ] road_right_side = [ lateral_shift(w.transform, w.lane_width * 0.5) for w in waypoints ] polygon = road_left_side + [x for x in reversed(road_right_side)] polygon = [ world_to_pixel( x, scale=scale, offset=world_offset, pixels_per_meter=pixels_per_meter, ) for x in polygon ] if len(polygon) > 2: pygame.draw.polygon(surface, COLORS["WHITE"], polygon, 5) pygame.draw.polygon(surface, COLORS["WHITE"], polygon) return surface