Skip to content

Latest commit

 

History

History
64 lines (47 loc) · 7.28 KB

File metadata and controls

64 lines (47 loc) · 7.28 KB
title sidebar_label sidebar_position toc_min_heading_level toc_max_heading_level
ROS 2 Sensors API
Sensors API
4
2
4

:::note

The '#' in the topic represents the index of the sensor. Indexing begins at 0 and will increment for each new sensor of that type that is added. Internal sensors such as IMU's will be indexed first.

:::

2D Lidar topics

Topic Message type Description QoS
sensors/lidar2d_#/scan sensor_msgs/LaserScan Lidar scan data System Default

3D Lidar topics

Topic Message type Description QoS
sensors/lidar3d_#/points sensor_msgs/PointCloud2 Lidar pointcloud data System Default
sensors/lidar3d_#/scan sensor_msgs/LaserScan Lidar scan data System Default
sensors/lidar3d_#/imu/data_raw sensor_msgs/Imu IMU data System Default

Camera topics

Topic Message type Description QoS
sensors/camera_#/color/image sensor_msgs/Image Raw RGB image System Default
sensors/camera_#/color/camera_info sensor_msgs/CameraInfo Camera Info System Default
sensors/camera_#/depth/image sensor_msgs/Image Raw depth image System Default
sensors/camera_#/depth/camera_info sensor_msgs/CameraInfo Camera Info System Default
sensors/camera_#/points sensor_msgs/PointCloud2 Pointcloud data System Default
sensors/camera_#/imu/data_raw sensor_msgs/Imu IMU data System Default

IMU topics

Topic Message type Description QoS
sensors/imu_#/data_raw sensor_msgs/Imu Raw IMU orientation, angular velocity, and linear acceleration data Sensor Data
sensors/imu_#/data sensor_msgs/Imu Filtered IMU orientation, angular velocity, and linear acceleration data System Default
sensors/imu_#/mag sensor_msgs/MagneticField IMU magnetic field data System Default

INS topics

Topic Message type Description QoS
sensors/ins_#/imu_0/data sensor_msgs/Imu Raw IMU orientation, angular velocity, and linear acceleration data Sensor Data
sensors/ins_#/gps_0/fix sensor_msgs/NavSatFix Navsat Fix information from the first receiver (if present) Sensor Data
sensors/ins_#/gps_1/fix sensor_msgs/NavSatFix Navsat Fix information from the second receiver (if present) Sensor Data
sensors/ins_#/odom nav_msgs/Odometry Odometry data derived from all inputs to the INS Sensor Data

GPS topics

Topic Message type Description QoS
sensors/gps_#/fix sensor_msgs/NavSatFix Navsat Fix information System Default