ROS Bridge Sensors


Available Sensors

RGB camera
Topic Type
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME>/image sensor_msgs/Image
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME>/camera_info sensor_msgs/CameraInfo
Depth camera
Topic Type
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME>/image sensor_msgs/Image
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME>/camera_info sensor_msgs/CameraInfo
Semantic segmentation camera
Topic Type
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME>/image sensor_msgs/Image
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME>/camera_info sensor_msgs/CameraInfo
DVS camera
Topic Type
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME>/events sensor_msgs/PointCloud2
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME>/image sensor_msgs/Image
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME>/camera_info sensor_msgs/CameraInfo
Lidar
Topic Type
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME> sensor_msgs/PointCloud2
Semantic lidar
Topic Type
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME> sensor_msgs/PointCloud2
Radar
Topic Type
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME> sensor_msgs/PointCloud2
IMU
Topic Type
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME> sensor_msgs/Imu
GNSS
Topic Type
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME> sensor_msgs/NavSatFix
Collision Sensor
Topic Type
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME> carla_msgs/CarlaCollisionEvent
Lane Invasion Sensor
Topic Type
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME> carla_msgs/CarlaLaneInvasionEvent

Pseudo sensors

TF Sensor

The tf data for the ego vehicle is published when this pseudo sensor is spawned.

Note: Sensors publish the tf data when the measurement is done. The child_frame_id corresponds with the prefix of the sensor topics.

Odometry Sensor
Topic Type Description
/carla/<PARENT ROLE NAME>/<SENSOR ROLE NAME> nav_msgs/Odometry Odometry of the parent actor.
Speedometer Sensor
Topic Type Description
/carla/<PARENT ROLE NAME>/<SENSOR ROLE NAME> std_msgs/Float32 Speed of the parent actor. Units: m/s.
Map Sensor
Topic Type Description
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME> std_msgs/String Provides the OpenDRIVE map as a string on a latched topic.
Object Sensor
Topic Type Description
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME> derived_object_msgs/ObjectArray Publishes all vehicles and walker. If attached to a parent, the parent is not contained.
Marker Sensor
Topic Type Description
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME> visualization_msgs/Marker Visualization of vehicles and walkers
Traffic Lights Sensor
Topic Type Description
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME>/status carla_msgs/CarlaTrafficLightStatusList List of all traffic lights with their status.
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME>/info carla_msgs/CarlaTrafficLightInfoList Static information for all traffic lights (e.g. position).
Actor List Sensor
Topic Type Description
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME> carla_msgs/CarlaActorList List of all CARLA actors.
Actor Control Sensor

This pseudo-sensor allows to control the position and velocity of the actor it is attached to (e.g. an ego_vehicle) by publishing pose and velocity within Pose and Twist datatypes. CAUTION: This control method does not respect the vehicle constraints. It allows movements impossible in the real world, like flying or rotating. Currently this sensor applies the complete linear vector, but only the yaw from angular vector.

Topic Type Description
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME>/set_transform geometry_msgs/Pose Transform to apply to the sensor's parent.
/carla/[<PARENT ROLE NAME>]/<SENSOR ROLE NAME>/set_target_velocity geometry_msgs/Twist Velocity (angular and linear) to apply to the sensor's parent.