def prepare_ngsim_scenario(client: carla.Client) -> Scenario: data_dir = os.environ.get("NGSIM_DIR") assert data_dir, "Path to the directory with NGSIM dataset is required" ngsim_map = NGSimDatasets.list() ngsim_dataset = random.choice(ngsim_map) client.load_world(ngsim_dataset.carla_map.level_path) return NGSimLaneChangeScenario( ngsim_dataset, dataset_mode=DatasetMode.TRAIN, data_dir=data_dir, reward_type=RewardType.DENSE, client=client, )
def spawn_npcs(carla_client: carla.Client, wpp: WaypointProvider = None, n=10, role_name_prefix='npc') -> List[BasicAgent]: world: carla.World = carla_client.get_world() vehicle_blueprints = world.get_blueprint_library().filter('vehicle.*') if not wpp: wpp = WaypointProvider(world) wpp.update(free_only=True) start_points: List[carla.Transform] = [] end_points: List[carla.Transform] = [] agent_ids: List[int] = [] agents: List[BasicAgent] = [] batch: List[carla.command.SpawnActor] = [] for i in range(n): blueprint = random.choice(vehicle_blueprints) blueprint.set_attribute('role_name', f'{role_name_prefix}_{i}') if blueprint.has_attribute('color'): color = random.choice( blueprint.get_attribute('color').recommended_values) blueprint.set_attribute('color', color) start_points.append(wpp.get()) end_points.append(wpp.get()) batch.append(carla.command.SpawnActor(blueprint, start_points[-1])) results = carla_client.apply_batch_sync(batch, True) for i in range(len(results)): if results[i].error: logging.error(results[i].error) else: agent_ids.append(results[i].actor_id) world.wait_for_tick() agent_actors: carla.ActorList = world.get_actors(agent_ids) for i, actor in enumerate(agent_actors): agent: BasicAgent = BasicAgent(actor, target_speed=NPC_TARGET_SPEED) try: agent.set_location_destination(end_points[i].location) agents.append(agent) except AttributeError: logging.error(f'Failed to spawn NPC actor with id {actor.id}.') return agents
def prepare_opendd_scenario(client: carla.Client) -> Scenario: data_dir = os.environ.get("OPENDD_DIR") assert data_dir, "Path to the directory with openDD dataset is required" maps = ["rdb1", "rdb2", "rdb3", "rdb4", "rdb5", "rdb6", "rdb7"] map_name = random.choice(maps) carla_map = getattr(CarlaMaps, map_name.upper()) client.load_world(carla_map.level_path) return OpenDDScenario( client, dataset_dir=data_dir, dataset_mode=DatasetMode.TRAIN, reward_type=RewardType.DENSE, place_name=map_name, )
def __init__(self, base_tile: QuadKey, ego_prefix: str, carla_client: carla.Client, rate: int = 10, data_dir: str = '/tmp'): self.killer: GracefulKiller = GracefulKiller() self.tick_rate: int = rate self.tick_timeout: float = 1 / rate self.data_dir: str = data_dir self.data_dir_actual: str = os.path.join(data_dir, 'actual') self.base_tile: QuadKey = base_tile self.ego_prefix: str = ego_prefix self.client: carla.Client = carla_client self.world: carla.World = carla_client.get_world() self.map: carla.Map = self.world.get_map() self.start_time: datetime = datetime.now() self.last_tick: float = 0 self.tick_count: int = 0 self.flush_count: int = 0 self.ground_truth_buffer: List[OccupancyGroundTruthContainer] = [] self.occupancy_ground_truth: List[OccupancyGroundTruthContainer] = [] for d in [self.data_dir, self.data_dir_actual]: if not os.path.exists(d): os.makedirs(d)
def __init__( self, client: carla.Client, target_size: PixelDimensions, render_lanes_on_junctions: bool, pixels_per_meter: int = 4, crop_type: BirdViewCropType = BirdViewCropType.FRONT_AND_REAR_AREA, ) -> None: self.client = client self.target_size = target_size self.pixels_per_meter = pixels_per_meter self._crop_type = crop_type if crop_type is BirdViewCropType.FRONT_AND_REAR_AREA: rendering_square_size = round( square_fitting_rect_at_any_rotation(self.target_size)) elif crop_type is BirdViewCropType.FRONT_AREA_ONLY: # We must keep rendering size from FRONT_AND_REAR_AREA (in order to avoid rotation issues) enlarged_size = PixelDimensions(width=target_size.width, height=target_size.height * 2) rendering_square_size = round( square_fitting_rect_at_any_rotation(enlarged_size)) else: raise NotImplementedError self.rendering_area = PixelDimensions(width=rendering_square_size, height=rendering_square_size) self._world = client.get_world() self._map = self._world.get_map() self.masks_generator = MapMaskGenerator( client, pixels_per_meter=pixels_per_meter, render_lanes_on_junctions=render_lanes_on_junctions, ) cache_path = self.parametrized_cache_path() with FileLock(f"{cache_path}.lock"): if Path(cache_path).is_file(): LOGGER.info(f"Loading cache from {cache_path}") static_cache = np.load(cache_path) self.full_road_cache = static_cache[0] self.full_lanes_cache = static_cache[1] self.full_centerlines_cache = static_cache[2] LOGGER.info( f"Loaded static layers from cache file: {cache_path}") else: LOGGER.warning( f"Cache file does not exist, generating cache at {cache_path}" ) self.full_road_cache = self.masks_generator.road_mask() self.full_lanes_cache = self.masks_generator.lanes_mask() self.full_centerlines_cache = self.masks_generator.centerlines_mask( ) static_cache = np.stack([ self.full_road_cache, self.full_lanes_cache, self.full_centerlines_cache, ]) np.save(cache_path, static_cache, allow_pickle=False) LOGGER.info(f"Saved static layers to cache file: {cache_path}")
def __init__(self, client: carla.Client, number_of_walkers) -> None: self.world = client.get_world() self.number_of_walkers = number_of_walkers self.blueprintsWalkers = self.world.get_blueprint_library().filter( 'walker.pedestrian.*') self.spawn_location_calculated = False self.spawnable_points = []
def get_world(host: str = "localhost", port: int = 2000, timeout: int = 10): """Get a handle to the world running inside the simulation. Args: host (:obj:`str`): The host where the simulator is running. port (:obj:`int`): The port to connect to at the given host. timeout (:obj:`int`): The timeout of the connection (in seconds). Returns: A tuple of `(client, world)` where the `client` is a connection to the simulator and `world` is a handle to the world running inside the simulation at the host:port. """ try: from carla import Client client = Client(host, port) client_version = client.get_client_version() server_version = client.get_server_version() err_msg = 'Simulator client {} does not match server {}'.format( client_version, server_version) assert client_version == server_version, err_msg client.set_timeout(timeout) world = client.get_world() except RuntimeError as r: raise Exception("Received an error while connecting to the " "simulator: {}".format(r)) except ImportError: raise Exception('Error importing CARLA.') return (client, world)
def main(): global world client = Client('localhost', 2000) world = client.get_world() settings = world.get_settings() settings.synchronous_mode = True settings.fixed_delta_seconds = 1.0 / 10 world.apply_settings(settings) # Spawn the vehicle. vehicle = spawn_driving_vehicle(client, world) # Spawn the camera and register a function to listen to the images. camera = spawn_rgb_camera(world, Location(x=2.0, y=0.0, z=1.8), Rotation(roll=0, pitch=0, yaw=0), vehicle) camera.listen(process_images) world.tick() return vehicle, camera, world
def spawn_vehicles(amount: int, blueprints: list, client: carla.Client, spawn_points: List[carla.Transform]) -> list: """Spawns vehicles, based on spawn_npc.py""" assert amount >= 0 traffic_manager = client.get_trafficmanager() batch = [] vehicles = [] random.shuffle(spawn_points) for i, transform in enumerate(spawn_points): if i >= amount: break blueprint = random.choice(blueprints) if blueprint.has_attribute('color'): color = random.choice( blueprint.get_attribute('color').recommended_values) blueprint.set_attribute('color', color) if blueprint.has_attribute('driver_id'): driver_id = random.choice( blueprint.get_attribute('driver_id').recommended_values) blueprint.set_attribute('driver_id', driver_id) blueprint.set_attribute('role_name', 'autopilot') # spawn the cars and set their autopilot batch.append( carla.command.SpawnActor(blueprint, transform).then( carla.command.SetAutopilot(carla.command.FutureActor, True, traffic_manager.get_port()))) for response in client.apply_batch_sync(batch, True): if response.error: print(response.error) else: vehicles.append(response.actor_id) return vehicles
def __init__(self, client: carla.Client): print("Available Maps:") print(client.get_available_maps()) client.load_world('Town04') client.reload_world() self.carla_world: carla.World = client.get_world() blueprint_library: carla.BlueprintLibrary = self.carla_world.get_blueprint_library( ) # Create vehicle vehicle_bp = blueprint_library.filter('vehicle.citroen.c3')[0] spawn_point = self.carla_world.get_map().get_spawn_points()[86] self.ego_vehicle: carla.Vehicle = self.carla_world.spawn_actor( vehicle_bp, spawn_point) self.ego_vehicle.set_autopilot(False) for idx, waypoint in enumerate( self.carla_world.get_map().get_spawn_points()): self.carla_world.debug.draw_string(waypoint.location, str(idx), draw_shadow=False, color=carla.Color(r=255, g=0, b=0), life_time=1000, persistent_lines=True) # Move spectator cam into a topview close to the spawn point self.carla_world.get_spectator().set_transform( carla.Transform( self.ego_vehicle.get_location() + carla.Location(x=0, y=-10, z=100.0), carla.Rotation(pitch=-80))) self.create_traffic(client, [88, 84, 73, 357])
def spawn_static_vehicles(carla_client: carla.Client, n=10, role_name_prefix='static') -> List[carla.Actor]: world: carla.World = carla_client.get_world() map: carla.Map = world.get_map() vehicle_blueprints = world.get_blueprint_library().filter('vehicle.*') actor_ids: List[int] = [] batch: List[carla.command.SpawnActor] = [] sidewalk_points: List[carla.Location] = [ world.get_random_location_from_navigation() for _ in range(n) ] street_points: List[carla.Transform] = [ map.get_waypoint(l).transform for l in sidewalk_points ] spawn_points: List[carla.Transform] = [ carla.Transform(location=sidewalk_points[i], rotation=street_points[i].rotation) for i in range(n) ] for i in range(len(spawn_points)): bp: carla.Blueprint = random.choice(vehicle_blueprints) bp.set_attribute('role_name', f'{role_name_prefix}_{i * 100}') batch.append(carla.command.SpawnActor(bp, spawn_points[i])) results = carla_client.apply_batch_sync(batch, True) for i in range(len(results)): if results[i].error: logging.error(results[i].error) else: actor_ids.append(results[i].actor_id) all_actors: carla.ActorList = world.get_actors(actor_ids) return [a for a in all_actors]
def setup_carla_settings(client: carla.Client, synchronous: bool, time_delta_s: float): world = client.get_world() settings = world.get_settings() changed = False if settings.synchronous_mode != synchronous: LOGGER.warning(f"Switch synchronous_mode={synchronous}") settings.synchronous_mode = synchronous changed = True if settings.fixed_delta_seconds != time_delta_s: LOGGER.warning(f"Change fixed_delta_seconds={time_delta_s}") settings.fixed_delta_seconds = time_delta_s changed = True if changed: world.apply_settings(settings)
def __init__(self, client: carla.Client, strategy: EgoStrategy = None, name: str = 'hero', render: bool = False, debug: bool = False, record: bool = False, is_standalone: bool = False, grid_radius: float = OCCUPANCY_RADIUS_DEFAULT, lidar_angle: float = LIDAR_ANGLE_DEFAULT): self.killer: GracefulKiller = GracefulKiller( ) if is_standalone else None self.sim: carla.Client = client self.client: TalkyClient = None self.world: carla.World = client.get_world() self.map: carla.Map = self.world.get_map() self.alive: bool = True self.name: str = name self.vehicle: carla.Vehicle = None self.player: carla.Vehicle = None # for compatibility self.grid: Grid = None self.hud: HUD = None self.strategy: EgoStrategy = strategy self.debug: bool = debug self.record: bool = record self.n_ticked: int = 0 self.display = None self.sensor_tick_pool: ThreadPool = ThreadPool(processes=6) self.sensors: Dict[str, carla.Sensor] = { 'gnss': None, 'lidar': None, 'camera_rgb': None, 'position': None, } # Initialize visual stuff if render: pygame.init() pygame.display.set_caption(f'PyGame – {name}') pygame.font.init() self.display = pygame.display.set_mode( (RES_X, RES_Y), pygame.HWSURFACE | pygame.DOUBLEBUF) self.hud = HUD(RES_X, RES_X) # Initialize strategy if not self.strategy: self.strategy = ManualEgoStrategy( ) if render else EmptyEgoStrategy() self.strategy.init(self) # Initialize callbacks if self.hud: self.world.on_tick(self.hud.on_world_tick) # Initialize player vehicle self.vehicle = self.strategy.player self.player = self.vehicle # Initialize Talky Client self.client = TalkyClient(for_subject_id=self.vehicle.id, dialect=ClientDialect.CARLA) self.client.gm.radius = grid_radius # Initialize sensors grid_range = grid_radius * QuadKey('0' * OCCUPANCY_TILE_LEVEL).side() lidar_min_range = (grid_range + .5) / math.cos( math.radians(lidar_angle)) lidar_range = min( LIDAR_MAX_RANGE, max(lidar_min_range, LIDAR_Z_OFFSET / math.sin(math.radians(lidar_angle))) * 2) self.sensors['gnss'] = GnssSensor(self.vehicle, self.client, offset_z=GNSS_Z_OFFSET) self.sensors['lidar'] = LidarSensor(self.vehicle, self.client, offset_z=LIDAR_Z_OFFSET, range=lidar_range, angle=lidar_angle) self.sensors['actors'] = ActorsSensor( self.vehicle, self.client, with_noise=True) # Set to false for evaluation self.sensors['position'] = PositionSensor(self.vehicle, self.client) if render: self.sensors['camera_rgb'] = CameraRGBSensor( self.vehicle, self.hud) # Initialize subscriptions def on_grid(grid: OccupancyGridObservation): self.grid = grid.value self.client.outbound.subscribe(OBS_GRID_LOCAL, on_grid) if is_standalone: lock = Lock() clock = pygame.time.Clock() def on_tick(*args): if lock.locked() or self.killer.kill_now: return lock.acquire() clock.tick_busy_loop(60) if self.tick(clock): self.killer.kill_now = True lock.release() self.world.on_tick(on_tick) while True: if self.killer.kill_now: try: self.destroy() return finally: return try: self.world.wait_for_tick() except RuntimeError: self.killer.kill_now = True continue
from carla import Client, Transform, Rotation, Location, Waypoint from carla import LaneMarking import carla import random import time import math import sys # starting proper work now print('attempting to connect...') # DEBUG client = Client('localhost', 2000, worker_threads=12) client.set_timeout(10.0) client.load_world('/Game/Carla/Maps/single_left_bend') print('connected!') # DEBUG world = client.get_world() # ################################################## # Change weather for data collection # ClearNoon, ClearSunset, WetSunset, WetNoon world.set_weather(carla.WeatherParameters.WetSunset) # ################################################## # bp of all actors blueprint_lib = world.get_blueprint_library() vehicle_bp = blueprint_lib.find('vehicle.audi.tt') lane_invasion_sensor_bp = blueprint_lib.find('sensor.other.lane_invasion')
def __init__(self, client: carla.Client): self._client = client self._world = client.get_world() self._world_map = self._world.get_map()
def try_spawn_pedestrians(carla_client: carla.Client, n=10) -> List[carla.Actor]: # ------------- # Spawn Walkers # ------------- world: carla.World = carla_client.get_world() walker_blueprints = world.get_blueprint_library().filter( 'walker.pedestrian.000[1-7]*') walkers_list = [] all_id = [] # 1. take all the random locations to spawn spawn_points = [] for i in range(n): spawn_point = carla.Transform() loc = world.get_random_location_from_navigation() if loc is not None: spawn_point.location = loc spawn_points.append(spawn_point) # 2. we spawn the walker object batch = [] for spawn_point in spawn_points: walker_bp = random.choice(walker_blueprints) # set as not invincible if walker_bp.has_attribute('is_invincible'): walker_bp.set_attribute('is_invincible', 'false') batch.append(carla.command.SpawnActor(walker_bp, spawn_point)) results = carla_client.apply_batch_sync(batch, True) for i in range(len(results)): if results[i].error: logging.error(results[i].error) else: walkers_list.append({"id": results[i].actor_id}) # 3. we spawn the walker controller batch = [] walker_controller_bp = world.get_blueprint_library().find( 'controller.ai.walker') for i in range(len(walkers_list)): batch.append( carla.command.SpawnActor(walker_controller_bp, carla.Transform(), walkers_list[i]["id"])) results = carla_client.apply_batch_sync(batch, True) for i in range(len(results)): if results[i].error: logging.error(results[i].error) else: walkers_list[i]["con"] = results[i].actor_id # 4. we put altogether the walkers and controllers id to get the objects from their id for i in range(len(walkers_list)): all_id.append(walkers_list[i]["con"]) all_id.append(walkers_list[i]["id"]) all_actors: carla.ActorList = world.get_actors(all_id) # wait for a tick to ensure client receives the last transform of the walkers we have just created world.wait_for_tick() # 5. initialize each controller and set target to walk to (list is [controller, actor, controller, actor ...]) for i in range(0, len(all_id), 2): # start walker all_actors[i].start() try: # set walk to random point all_actors[i].go_to_location( world.get_random_location_from_navigation()) # random max speed all_actors[i].set_max_speed( 1 + random.random() ) # max speed between 1 and 2 (default is 1.4 m/s) except Exception as e: all_actors[i].stop() all_actors = all_actors[:i] + all_actors[i + 2:] return [a for a in all_actors]
def multi_destroy(carla_client: carla.Client, actors: Iterable[carla.Actor]): batch = list(map(lambda a: carla.command.DestroyActor(a), actors)) carla_client.apply_batch_sync(batch, True)
def spawn_pedestrians(amount: int, blueprints: list, client: carla.Client, running=0.0, crossing=0.0) -> list: """Spawns pedestrians, based on spawn_npc.py""" assert amount >= 0 assert 0.0 <= running <= 1.0 assert 0.0 <= crossing <= 1.0 percentage_pedestrians_running = running # how many pedestrians will run percentage_pedestrians_crossing = crossing # how many pedestrians will walk through the road traffic_manager = client.get_trafficmanager() world = client.get_world() # 1. Spawn point with random location (for navigation purpose) spawn_points = [] for i in range(amount): spawn_point = carla.Transform() loc = world.get_random_location_from_navigation() if loc is not None: spawn_point.location = loc spawn_points.append(spawn_point) # 2. spawn the walker object batch = [] walker_speed = [] for spawn_point in spawn_points: walker_bp = random.choice(blueprints) # set as not invincible if walker_bp.has_attribute('is_invincible'): walker_bp.set_attribute('is_invincible', 'false') # set the max speed if walker_bp.has_attribute('speed'): if random.random() > percentage_pedestrians_running: # walking walker_speed.append( walker_bp.get_attribute('speed').recommended_values[1]) else: # running walker_speed.append( walker_bp.get_attribute('speed').recommended_values[2]) else: print("Walker has no speed") walker_speed.append(0.0) batch.append(carla.command.SpawnActor(walker_bp, spawn_point)) results = client.apply_batch_sync(batch, True) walker_speed2 = [] walkers = [] for i in range(len(results)): if results[i].error: print(results[i].error) else: walkers.append(dict(id=results[i].actor_id, controller=None)) walker_speed2.append(walker_speed[i]) walker_speed = walker_speed2 # 3. Spawn the walker controller batch = [] walker_controller_bp = world.get_blueprint_library().find( 'controller.ai.walker') for i in range(len(walkers)): batch.append( carla.command.SpawnActor(walker_controller_bp, carla.Transform(), walkers[i]['id'])) results = client.apply_batch_sync(batch, True) for i in range(len(results)): if results[i].error: print(results[i].error) else: walkers[i]['controller'] = results[i].actor_id # 4. Put altogether the walkers and controllers id to get the objects from their id all_id = [] for i in range(len(walkers)): all_id.append(walkers[i]['controller']) all_id.append(walkers[i]['id']) all_actors = world.get_actors(all_id) # wait for a tick to ensure client receives the last transform of the walkers we have just created if not world.get_settings().synchronous_mode: world.wait_for_tick() else: world.tick() # 5. initialize each controller and set target to walk to (list is [controller, actor, controller, actor ...]) # set how many pedestrians can cross the road world.set_pedestrians_cross_factor(percentage_pedestrians_crossing) for i in range(0, len(all_id), 2): # start walker all_actors[i].start() # set walk to random point all_actors[i].go_to_location( world.get_random_location_from_navigation()) # max speed all_actors[i].set_max_speed(float(walker_speed[int(i / 2)])) return all_id
def __init__(self, client: carla.Client): self.client = client self.world = client.get_world() self.library = self.world.get_blueprint_library() self.spawned: List[ActorId] = []