def setup_sensors(self, vehicle, debug_mode=False): """ Create the sensors defined by the user and attach them to the ego-vehicle :param vehicle: ego vehicle :return: """ bp_library = CarlaDataProvider.get_world().get_blueprint_library() for sensor_spec in self._agent.sensors(): # These are the sensors spawned on the carla world bp = bp_library.find(str(sensor_spec['type'])) if sensor_spec['type'].startswith('sensor.camera'): bp.set_attribute('image_size_x', str(sensor_spec['width'])) bp.set_attribute('image_size_y', str(sensor_spec['height'])) bp.set_attribute('fov', str(sensor_spec['fov'])) sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], roll=sensor_spec['roll'], yaw=sensor_spec['yaw']) elif sensor_spec['type'].startswith('sensor.lidar'): bp.set_attribute('range', str(sensor_spec['range'])) bp.set_attribute('rotation_frequency', str(sensor_spec['rotation_frequency'])) bp.set_attribute('channels', str(sensor_spec['channels'])) bp.set_attribute('upper_fov', str(sensor_spec['upper_fov'])) bp.set_attribute('lower_fov', str(sensor_spec['lower_fov'])) bp.set_attribute('points_per_second', str(sensor_spec['points_per_second'])) sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'], roll=sensor_spec['roll'], yaw=sensor_spec['yaw']) elif sensor_spec['type'].startswith('sensor.other.gnss'): sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation() # create sensor sensor_transform = carla.Transform(sensor_location, sensor_rotation) sensor = CarlaDataProvider.get_world().spawn_actor( bp, sensor_transform, vehicle) # setup callback sensor.listen( CallBack(sensor_spec['id'], sensor, self._agent.sensor_interface)) self._sensors_list.append(sensor) while not self._agent.all_sensors_ready(): if debug_mode: print(" waiting for one data reading from sensors...") CarlaDataProvider.perform_carla_tick()
def __init__(self, name, ego_vehicles, config, world, debug_mode=False, terminate_on_failure=False, criteria_enable=False): """ Setup all relevant parameters and create scenario and instantiate scenario manager """ self.other_actors = [] if not self.timeout: # pylint: disable=access-member-before-definition self.timeout = 60 # If no timeout was provided, set it to 60 seconds self.criteria_list = [] # List of evaluation criteria self.scenario = None # Check if the CARLA server uses the correct map self._town = config.town self._check_town(world) self.ego_vehicles = ego_vehicles self.name = name self.terminate_on_failure = terminate_on_failure # Initializing adversarial actors self._initialize_actors(config) if world.get_settings().synchronous_mode: CarlaDataProvider.perform_carla_tick() else: world.wait_for_tick() # Setup scenario if debug_mode: py_trees.logging.level = py_trees.logging.Level.DEBUG behavior = self._create_behavior() criteria = None if criteria_enable: criteria = self._create_test_criteria() # Add a trigger condition for the behavior to ensure the behavior is only activated, when it is relevant behavior_seq = py_trees.composites.Sequence() trigger_behavior = self._setup_scenario_trigger(config) if trigger_behavior: behavior_seq.add_child(trigger_behavior) if behavior is not None: behavior_seq.add_child(behavior) behavior_seq.name = behavior.name self.scenario = Scenario(behavior_seq, criteria, self.name, self.timeout, self.terminate_on_failure)
def _load_and_wait_for_world(self, town, ego_vehicles=None): """ Load a new CARLA world and provide data to CarlaActorPool and CarlaDataProvider """ if self._args.reloadWorld: self.world = self.client.load_world(town) else: # if the world should not be reloaded, wait at least until all ego vehicles are ready ego_vehicle_found = False if self._args.waitForEgo: while not ego_vehicle_found and not self._shutdown_requested: vehicles = self.client.get_world().get_actors().filter( 'vehicle.*') for ego_vehicle in ego_vehicles: ego_vehicle_found = False for vehicle in vehicles: if vehicle.attributes[ 'role_name'] == ego_vehicle.rolename: ego_vehicle_found = True break if not ego_vehicle_found: print("Not all ego vehicles ready. Waiting ... ") time.sleep(1) break self.world = self.client.get_world() CarlaActorPool.set_client(self.client) CarlaActorPool.set_world(self.world) CarlaDataProvider.set_world(self.world) settings = self.world.get_settings() settings.fixed_delta_seconds = 1.0 / self.frame_rate self.world.apply_settings(settings) if self._args.agent: settings = self.world.get_settings() settings.synchronous_mode = True self.world.apply_settings(settings) # Wait for the world to be ready if self.world.get_settings().synchronous_mode: CarlaDataProvider.perform_carla_tick() else: self.world.wait_for_tick() if CarlaDataProvider.get_map( ).name != town and CarlaDataProvider.get_map().name != "OpenDriveMap": print("The CARLA server uses the wrong map: {}".format( CarlaDataProvider.get_map().name)) print("This scenario requires to use map: {}".format(town)) return False return True
def _tick_scenario(self, timestamp): """ Run next tick of scenario This function is a callback for world.on_tick() Important: - It has to be ensured that the scenario has not yet completed/failed and that the time moved forward. - A thread lock should be used to avoid that the scenario tick is performed multiple times in parallel. """ if self._timestamp_last_run < timestamp.elapsed_seconds and self._running: self._timestamp_last_run = timestamp.elapsed_seconds self._watchdog.update() if self._debug_mode: print("\n--------- Tick ---------\n") # Update game time and actor information GameTime.on_carla_tick(timestamp) CarlaDataProvider.on_carla_tick() if self._agent is not None: ego_action = self._agent() # Tick scenario self.scenario_tree.tick_once() if self._debug_mode: print("\n") py_trees.display.print_ascii_tree(self.scenario_tree, show_status=True) sys.stdout.flush() if self.scenario_tree.status != py_trees.common.Status.RUNNING: self._running = False if self._challenge_mode: ChallengeStatisticsManager.compute_current_statistics() if self._agent is not None: self.ego_vehicles[0].apply_control(ego_action) if self._agent and self._running and self._watchdog.get_status(): CarlaDataProvider.perform_carla_tick(self._timeout)
def _prepare_ego_vehicles(self, ego_vehicles): """ Spawn or update the ego vehicles """ if not self._args.waitForEgo: for vehicle in ego_vehicles: self.ego_vehicles.append( CarlaActorPool.setup_actor( vehicle.model, vehicle.transform, vehicle.rolename, True, color=vehicle.color, actor_category=vehicle.category)) else: ego_vehicle_missing = True while ego_vehicle_missing: self.ego_vehicles = [] ego_vehicle_missing = False for ego_vehicle in ego_vehicles: ego_vehicle_found = False carla_vehicles = CarlaDataProvider.get_world().get_actors( ).filter('vehicle.*') for carla_vehicle in carla_vehicles: if carla_vehicle.attributes[ 'role_name'] == ego_vehicle.rolename: ego_vehicle_found = True self.ego_vehicles.append(carla_vehicle) break if not ego_vehicle_found: ego_vehicle_missing = True break for i, _ in enumerate(self.ego_vehicles): self.ego_vehicles[i].set_transform(ego_vehicles[i].transform) # sync state CarlaDataProvider.perform_carla_tick()
def _build_scenario_instances(self, world, ego_vehicle, scenario_definitions, town, scenarios_per_tick=5, timeout=300, debug_mode=False): """ Based on the parsed route and possible scenarios, build all the scenario classes. """ scenario_instance_vec = [] if debug_mode: for scenario in scenario_definitions: loc = carla.Location( scenario['trigger_position']['x'], scenario['trigger_position']['y'], scenario['trigger_position']['z']) + carla.Location(z=2.0) world.debug.draw_point(loc, size=1.0, color=carla.Color(255, 0, 0), life_time=100000) world.debug.draw_string(loc, str(scenario['name']), draw_shadow=False, color=carla.Color(0, 0, 255), life_time=100000, persistent_lines=True) for scenario_number, definition in enumerate(scenario_definitions): # Get the class possibilities for this scenario number scenario_class = NUMBER_CLASS_TRANSLATION[definition['name']] # Create the other actors that are going to appear if definition['other_actors'] is not None: list_of_actor_conf_instances = self._get_actors_instances( definition['other_actors']) else: list_of_actor_conf_instances = [] # Create an actor configuration for the ego-vehicle trigger position egoactor_trigger_position = convert_json_to_transform( definition['trigger_position']) scenario_configuration = ScenarioConfiguration() scenario_configuration.other_actors = list_of_actor_conf_instances scenario_configuration.town = town scenario_configuration.trigger_points = [egoactor_trigger_position] scenario_configuration.subtype = definition['scenario_type'] scenario_configuration.ego_vehicles = [ ActorConfigurationData('vehicle.lincoln.mkz2017', ego_vehicle.get_transform(), 'hero') ] route_var_name = "ScenarioRouteNumber{}".format(scenario_number) scenario_configuration.route_var_name = route_var_name try: scenario_instance = scenario_class(world, [ego_vehicle], scenario_configuration, criteria_enable=False, timeout=timeout) # Do a tick every once in a while to avoid spawning everything at the same time if scenario_number % scenarios_per_tick == 0: sync_mode = world.get_settings().synchronous_mode if sync_mode: CarlaDataProvider.perform_carla_tick() else: world.wait_for_tick() scenario_number += 1 except Exception as e: # pylint: disable=broad-except if debug_mode: traceback.print_exc() print("Skipping scenario '{}' due to setup error: {}".format( definition['name'], e)) continue scenario_instance_vec.append(scenario_instance) return scenario_instance_vec
def setup_sensors(self, vehicle, debug_mode=False): """ Create the sensors defined by the user and attach them to the ego-vehicle :param vehicle: ego vehicle :return: """ bp_library = CarlaDataProvider.get_world().get_blueprint_library() for sensor_spec in self._agent.sensors(): # These are the pseudosensors (not spawned) if sensor_spec['type'].startswith('sensor.scene_layout'): # Static sensor that gives you the entire information from the world (Just runs once) sensor = SceneLayoutReader(CarlaDataProvider.get_world()) elif sensor_spec['type'].startswith('sensor.object_finder'): # This sensor returns the position of the dynamic objects in the scene. sensor = ObjectFinder(CarlaDataProvider.get_world(), sensor_spec['reading_frequency']) elif sensor_spec['type'].startswith('sensor.can_bus'): # The speedometer pseudo sensor is created directly here sensor = CANBusSensor(vehicle, sensor_spec['reading_frequency']) elif sensor_spec['type'].startswith('sensor.hd_map'): # The HDMap pseudo sensor is created directly here sensor = HDMapReader(vehicle, sensor_spec['reading_frequency']) # These are the sensors spawned on the carla world else: bp = bp_library.find(str(sensor_spec['type'])) if sensor_spec['type'].startswith('sensor.camera'): bp.set_attribute('image_size_x', str(sensor_spec['width'])) bp.set_attribute('image_size_y', str(sensor_spec['height'])) bp.set_attribute('fov', str(sensor_spec['fov'])) sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation( pitch=sensor_spec['pitch'], roll=sensor_spec['roll'], yaw=sensor_spec['yaw']) elif sensor_spec['type'].startswith('sensor.lidar'): bp.set_attribute('range', str(sensor_spec['range'])) bp.set_attribute('rotation_frequency', str(sensor_spec['rotation_frequency'])) bp.set_attribute('channels', str(sensor_spec['channels'])) bp.set_attribute('upper_fov', str(sensor_spec['upper_fov'])) bp.set_attribute('lower_fov', str(sensor_spec['lower_fov'])) bp.set_attribute('points_per_second', str(sensor_spec['points_per_second'])) sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation( pitch=sensor_spec['pitch'], roll=sensor_spec['roll'], yaw=sensor_spec['yaw']) elif sensor_spec['type'].startswith('sensor.other.gnss'): sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'], z=sensor_spec['z']) sensor_rotation = carla.Rotation() # create sensor sensor_transform = carla.Transform(sensor_location, sensor_rotation) sensor = CarlaDataProvider.get_world().spawn_actor( bp, sensor_transform, vehicle) # setup callback sensor.listen( CallBack(sensor_spec['id'], sensor, self._agent.sensor_interface)) self._sensors_list.append(sensor) self._validate_sensor_configuration() while not self._agent.all_sensors_ready(): if debug_mode: print(" waiting for one data reading from sensors...") CarlaDataProvider.perform_carla_tick()