def _create_object(self, uid, type_id, name, attach_to, spawn_pose, carla_actor=None): # check that the actor is not already created. if carla_actor is not None and carla_actor.id in self.actors: return None if attach_to != 0: if attach_to not in self.actors: raise IndexError( "Parent object {} not found".format(attach_to)) parent = self.actors[attach_to] else: parent = None if type_id == TFSensor.get_blueprint_name(): actor = TFSensor(uid=uid, name=name, parent=parent, node=self.node) elif type_id == OdometrySensor.get_blueprint_name(): actor = OdometrySensor(uid=uid, name=name, parent=parent, node=self.node) elif type_id == SpeedometerSensor.get_blueprint_name(): actor = SpeedometerSensor(uid=uid, name=name, parent=parent, node=self.node) elif type_id == MarkerSensor.get_blueprint_name(): actor = MarkerSensor(uid=uid, name=name, parent=parent, node=self.node, actor_list=self.actors) elif type_id == ActorListSensor.get_blueprint_name(): actor = ActorListSensor(uid=uid, name=name, parent=parent, node=self.node, actor_list=self.actors) elif type_id == ObjectSensor.get_blueprint_name(): actor = ObjectSensor( uid=uid, name=name, parent=parent, node=self.node, actor_list=self.actors, ) elif type_id == TrafficLightsSensor.get_blueprint_name(): actor = TrafficLightsSensor( uid=uid, name=name, parent=parent, node=self.node, actor_list=self.actors, ) elif type_id == OpenDriveSensor.get_blueprint_name(): actor = OpenDriveSensor(uid=uid, name=name, parent=parent, node=self.node, carla_map=self.world.get_map()) elif type_id == ActorControl.get_blueprint_name(): actor = ActorControl(uid=uid, name=name, parent=parent, node=self.node) elif carla_actor.type_id.startswith('traffic'): if carla_actor.type_id == "traffic.traffic_light": actor = TrafficLight(uid, name, parent, self.node, carla_actor) else: actor = Traffic(uid, name, parent, self.node, carla_actor) elif carla_actor.type_id.startswith("vehicle"): if carla_actor.attributes.get('role_name')\ in self.node.parameters['ego_vehicle']['role_name']: actor = EgoVehicle( uid, name, parent, self.node, carla_actor, self.node._ego_vehicle_control_applied_callback) else: actor = Vehicle(uid, name, parent, self.node, carla_actor) elif carla_actor.type_id.startswith("sensor"): if carla_actor.type_id.startswith("sensor.camera"): if carla_actor.type_id.startswith("sensor.camera.rgb"): actor = RgbCamera(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.camera.depth"): actor = DepthCamera(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith( "sensor.camera.semantic_segmentation"): actor = SemanticSegmentationCamera(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.camera.dvs"): actor = DVSCamera(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) else: actor = Camera(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.lidar"): if carla_actor.type_id.endswith("sensor.lidar.ray_cast"): actor = Lidar(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.endswith( "sensor.lidar.ray_cast_semantic"): actor = SemanticLidar(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.radar"): actor = Radar(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.gnss"): actor = Gnss(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.imu"): actor = ImuSensor(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.collision"): actor = CollisionSensor(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.rss"): actor = RssSensor(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.lane_invasion"): actor = LaneInvasionSensor(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) else: actor = Sensor(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("spectator"): actor = Spectator(uid, name, parent, self.node, carla_actor) elif carla_actor.type_id.startswith("walker"): actor = Walker(uid, name, parent, self.node, carla_actor) else: actor = Actor(uid, name, parent, self.node, carla_actor) self.actors[actor.uid] = actor self.node.loginfo("Created {}(id={})".format(actor.__class__.__name__, actor.uid)) return actor
def __init__(self, carla_world, params): """ Constructor :param carla_world: carla world object :type carla_world: carla.World :param params: dict of parameters, see settings.yaml :type params: dict """ rospy.init_node("carla_bridge", anonymous=True) self.parameters = params self.actors = {} self.carla_world = carla_world self.synchronous_mode_update_thread = None # set carla world settings self.carla_settings = carla_world.get_settings() rospy.loginfo("synchronous_mode: {}".format( self.parameters["synchronous_mode"])) self.carla_settings.synchronous_mode = self.parameters[ "synchronous_mode"] rospy.loginfo("fixed_delta_seconds: {}".format( self.parameters["fixed_delta_seconds"])) self.carla_settings.fixed_delta_seconds = self.parameters[ "fixed_delta_seconds"] carla_world.apply_settings(self.carla_settings) self.comm = Communication() self.update_lock = Lock() self.carla_control_queue = queue.Queue() self.status_publisher = CarlaStatusPublisher( self.carla_settings.synchronous_mode) if self.carla_settings.synchronous_mode: self.carla_run_state = CarlaControl.PLAY self.carla_control_subscriber = \ rospy.Subscriber("/carla/control", CarlaControl, lambda control: self.carla_control_queue.put(control.command)) self.synchronous_mode_update_thread = Thread( target=self._synchronous_mode_update) self.synchronous_mode_update_thread.start() else: self.timestamp_last_run = 0.0 # register callback to create/delete actors self.update_child_actors_lock = Lock() self.carla_world.on_tick(self._carla_update_child_actors) # register callback to update actors self.carla_world.on_tick(self._carla_time_tick) self.pseudo_actors = [] # add map self.pseudo_actors.append( Map(carla_world=self.carla_world, communication=self.comm)) # add global object sensor self.pseudo_actors.append( ObjectSensor(parent=None, communication=self.comm, actor_list=self.actors, filtered_id=None))
def _create_actor(self, carla_actor): # pylint: disable=too-many-branches,too-many-statements """ create an actor """ parent = None if carla_actor.parent: if carla_actor.parent.id in self.actors: parent = self.actors[carla_actor.parent.id] else: parent = self._create_actor(carla_actor.parent) actor = None pseudo_actors = [] if carla_actor.type_id.startswith('traffic'): if carla_actor.type_id == "traffic.traffic_light": actor = TrafficLight(carla_actor, parent, self.comm) else: actor = Traffic(carla_actor, parent, self.comm) elif carla_actor.type_id.startswith("vehicle"): if carla_actor.attributes.get('role_name')\ in self.parameters['ego_vehicle']['role_name']: ego_vehicle = EgoVehicle(carla_actor, parent, self.comm) actor = ego_vehicle pseudo_actors.append( ObjectSensor(parent=ego_vehicle, communication=self.comm, actor_list=self.actors, filtered_id=carla_actor.id)) else: actor = Vehicle(carla_actor, parent, self.comm) elif carla_actor.type_id.startswith("sensor"): if carla_actor.type_id.startswith("sensor.camera"): if carla_actor.type_id.startswith("sensor.camera.rgb"): actor = RgbCamera(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.camera.depth"): actor = DepthCamera(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith( "sensor.camera.semantic_segmentation"): actor = SemanticSegmentationCamera( carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) else: actor = Camera(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.lidar"): actor = Lidar(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.gnss"): actor = Gnss(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.collision"): actor = CollisionSensor(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("sensor.other.lane_invasion"): actor = LaneInvasionSensor( carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) else: actor = Sensor(carla_actor, parent, self.comm, self.carla_settings.synchronous_mode) elif carla_actor.type_id.startswith("spectator"): actor = Spectator(carla_actor, parent, self.comm) elif carla_actor.type_id.startswith("walker"): actor = Walker(carla_actor, parent, self.comm) else: actor = Actor(carla_actor, parent, self.comm) rospy.loginfo("Created {}(id={}, parent_id={}," " type={}, prefix={}, attributes={})".format( actor.__class__.__name__, actor.get_id(), actor.get_parent_id(), carla_actor.type_id, actor.get_prefix(), carla_actor.attributes)) with self.update_lock: self.actors[carla_actor.id] = actor for pseudo_actor in pseudo_actors: rospy.loginfo("Created {}(parent_id={}, prefix={})".format( pseudo_actor.__class__.__name__, pseudo_actor.get_parent_id(), pseudo_actor.get_prefix())) with self.update_lock: self.pseudo_actors.append(pseudo_actor) return actor
def __init__(self, carla_world, params): """ Constructor :param carla_world: carla world object :type carla_world: carla.World :param params: dict of parameters, see settings.yaml :type params: dict """ # check CARLA version dist = pkg_resources.get_distribution("carla") if LooseVersion(dist.version) < LooseVersion(self.CARLA_VERSION): raise ImportError( "CARLA version {} or newer required. CARLA version found: {}". format(self.CARLA_VERSION, dist)) self.parameters = params self.actors = {} self.pseudo_actors = [] self.carla_world = carla_world self.synchronous_mode_update_thread = None self.shutdown = Event() # set carla world settings self.carla_settings = carla_world.get_settings() # workaround: settings can only applied within non-sync mode if self.carla_settings.synchronous_mode: self.carla_settings.synchronous_mode = False carla_world.apply_settings(self.carla_settings) rospy.loginfo("synchronous_mode: {}".format( self.parameters["synchronous_mode"])) self.carla_settings.synchronous_mode = self.parameters[ "synchronous_mode"] rospy.loginfo("fixed_delta_seconds: {}".format( self.parameters["fixed_delta_seconds"])) self.carla_settings.fixed_delta_seconds = self.parameters[ "fixed_delta_seconds"] carla_world.apply_settings(self.carla_settings) self.comm = Communication() self.update_lock = Lock() self.carla_control_queue = queue.Queue() self.status_publisher = CarlaStatusPublisher( self.carla_settings.synchronous_mode, self.carla_settings.fixed_delta_seconds) # for waiting for ego vehicle control commands in synchronous mode, # their ids are maintained in a list. # Before tick(), the list is filled and the loop waits until the list is empty. self._all_vehicle_control_commands_received = Event() self._expected_ego_vehicle_control_command_ids = [] self._expected_ego_vehicle_control_command_ids_lock = Lock() if self.carla_settings.synchronous_mode: self.carla_run_state = CarlaControl.PLAY self.carla_control_subscriber = \ rospy.Subscriber("/carla/control", CarlaControl, lambda control: self.carla_control_queue.put(control.command)) self.synchronous_mode_update_thread = Thread( target=self._synchronous_mode_update) self.synchronous_mode_update_thread.start() else: self.timestamp_last_run = 0.0 self.update_actors_queue = queue.Queue(maxsize=1) # start thread to update actors self.update_actor_thread = Thread( target=self._update_actors_thread) self.update_actor_thread.start() # create initially existing actors self.update_actors_queue.put( set([x.id for x in self.carla_world.get_snapshot()])) # wait for first actors creation to be finished self.update_actors_queue.join() # register callback to update actors self.on_tick_id = self.carla_world.on_tick(self._carla_time_tick) # add world info self.pseudo_actors.append( WorldInfo(carla_world=self.carla_world, communication=self.comm)) # add global object sensor self.pseudo_actors.append( ObjectSensor(parent=None, communication=self.comm, actor_list=self.actors, filtered_id=None)) self.debug_helper = DebugHelper(carla_world.debug) # add traffic light pseudo sensor self.pseudo_actors.append( TrafficLightsSensor(parent=None, communication=self.comm, actor_list=self.actors))
def __init__(self, carla_world, params): """ Constructor :param carla_world: carla world object :type carla_world: carla.World :param params: dict of parameters, see settings.yaml :type params: dict """ self.parameters = params self.actors = {} self.pseudo_actors = [] self.carla_world = carla_world self.synchronous_mode_update_thread = None self.shutdown = Event() # set carla world settings self.carla_settings = carla_world.get_settings() # workaround: settings can only applied within non-sync mode if self.carla_settings.synchronous_mode: self.carla_settings.synchronous_mode = False carla_world.apply_settings(self.carla_settings) rospy.loginfo("synchronous_mode: {}".format( self.parameters["synchronous_mode"])) self.carla_settings.synchronous_mode = self.parameters["synchronous_mode"] rospy.loginfo("fixed_delta_seconds: {}".format( self.parameters["fixed_delta_seconds"])) self.carla_settings.fixed_delta_seconds = self.parameters["fixed_delta_seconds"] carla_world.apply_settings(self.carla_settings) self.update_lock = Lock() self.carla_control_queue = queue.Queue() # Communication topics self.clock_publisher = rospy.Publisher('clock', Clock, queue_size=10) self.tf_publisher = rospy.Publisher('tf', TFMessage, queue_size=100) self.marker_publisher = rospy.Publisher('/carla/marker', Marker, queue_size=10) self.actor_list_publisher = rospy.Publisher('/carla/actor_list', CarlaActorList, queue_size=10, latch=True) self.status_publisher = CarlaStatusPublisher( self.carla_settings.synchronous_mode, self.carla_settings.fixed_delta_seconds) # for waiting for ego vehicle control commands in synchronous mode, # their ids are maintained in a list. # Before tick(), the list is filled and the loop waits until the list is empty. self._all_vehicle_control_commands_received = Event() self._expected_ego_vehicle_control_command_ids = [] self._expected_ego_vehicle_control_command_ids_lock = Lock() if self.carla_settings.synchronous_mode: self.carla_run_state = CarlaControl.PLAY self.carla_control_subscriber = \ rospy.Subscriber("/carla/control", CarlaControl, lambda control: self.carla_control_queue.put(control.command)) self.synchronous_mode_update_thread = Thread( target=self._synchronous_mode_update) self.synchronous_mode_update_thread.start() else: self.timestamp_last_run = 0.0 self.update_actors_queue = queue.Queue(maxsize=1) # start thread to update actors self.update_actor_thread = Thread( target=self._update_actors_thread) self.update_actor_thread.start() # create initially existing actors self.update_actors_queue.put( set([x.id for x in self.carla_world.get_snapshot()])) # wait for first actors creation to be finished self.update_actors_queue.join() # register callback to update actors self.on_tick_id = self.carla_world.on_tick(self._carla_time_tick) self.carla_weather_subscriber = \ rospy.Subscriber("/carla/weather_control", CarlaWeatherParameters, self.on_weather_changed) # add world info self.pseudo_actors.append(WorldInfo(carla_world=self.carla_world, node=self)) # add global object sensor self.pseudo_actors.append(ObjectSensor(parent=None, node=self, actor_list=self.actors, filtered_id=None)) self.debug_helper = DebugHelper(carla_world.debug) # add traffic light pseudo sensor self.pseudo_actors.append(TrafficLightsSensor(parent=None, node=self, actor_list=self.actors))
def _create_object(self, uid, type_id, name, parent, spawn_pose, carla_actor=None): if type_id == TFSensor.get_blueprint_name(): actor = TFSensor(uid=uid, name=name, parent=parent, node=self.node) elif type_id == OdometrySensor.get_blueprint_name(): actor = OdometrySensor(uid=uid, name=name, parent=parent, node=self.node) elif type_id == SpeedometerSensor.get_blueprint_name(): actor = SpeedometerSensor(uid=uid, name=name, parent=parent, node=self.node) elif type_id == MarkerSensor.get_blueprint_name(): actor = MarkerSensor(uid=uid, name=name, parent=parent, node=self.node, actor_list=self.actors) elif type_id == ActorListSensor.get_blueprint_name(): actor = ActorListSensor(uid=uid, name=name, parent=parent, node=self.node, actor_list=self.actors) elif type_id == ObjectSensor.get_blueprint_name(): actor = ObjectSensor( uid=uid, name=name, parent=parent, node=self.node, actor_list=self.actors, ) elif type_id == TrafficLightsSensor.get_blueprint_name(): actor = TrafficLightsSensor( uid=uid, name=name, parent=parent, node=self.node, actor_list=self.actors, ) elif type_id == OpenDriveSensor.get_blueprint_name(): actor = OpenDriveSensor(uid=uid, name=name, parent=parent, node=self.node, carla_map=self.world.get_map()) elif type_id == ActorControl.get_blueprint_name(): actor = ActorControl(uid=uid, name=name, parent=parent, node=self.node) elif carla_actor.type_id.startswith('traffic'): if carla_actor.type_id == "traffic.traffic_light": actor = TrafficLight(uid, name, parent, self.node, carla_actor) else: actor = Traffic(uid, name, parent, self.node, carla_actor) elif carla_actor.type_id.startswith("vehicle"): if carla_actor.attributes.get('role_name')\ in self.node.parameters['ego_vehicle']['role_name']: actor = EgoVehicle( uid, name, parent, self.node, carla_actor, self.node._ego_vehicle_control_applied_callback) else: actor = Vehicle(uid, name, parent, self.node, carla_actor) elif carla_actor.type_id.startswith("sensor"): if carla_actor.type_id.startswith("sensor.camera"): if carla_actor.type_id.startswith("sensor.camera.rgb"): actor = RgbCamera(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.camera.depth"): actor = DepthCamera(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith( "sensor.camera.semantic_segmentation"): actor = SemanticSegmentationCamera(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.camera.dvs"): actor = DVSCamera(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) else: actor = Camera(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.lidar"): if carla_actor.type_id.endswith("sensor.lidar.ray_cast"): actor = Lidar(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.endswith( "sensor.lidar.ray_cast_semantic"): actor = SemanticLidar(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.radar"): actor = Radar(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.gnss"): actor = Gnss(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.imu"): actor = ImuSensor(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.collision"): actor = CollisionSensor(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.rss"): actor = RssSensor(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("sensor.other.lane_invasion"): actor = LaneInvasionSensor(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) else: actor = Sensor(uid, name, parent, spawn_pose, self.node, carla_actor, self.sync_mode) elif carla_actor.type_id.startswith("spectator"): actor = Spectator(uid, name, parent, self.node, carla_actor) elif carla_actor.type_id.startswith("walker"): actor = Walker(uid, name, parent, self.node, carla_actor) else: actor = Actor(uid, name, parent, self.node, carla_actor) return actor