ROS & ROS2
The ROS wrapper allows you to use Intel RealSense Depth Cameras with ROS and ROS2.
The ROS Wrapper Releases (latest and previous versions), can be found at Intel RealSense ROS releases
These are the ROS2 supported Distributions:
- Rolling Ridley (Ubuntu 22.04 Jammy Jellyfish) - in Development phase
- Humble Hawksbill (Ubuntu 22.04 Jammy Jellyfish)
- Foxy Fitzroy (Ubuntu 20.04 Focal)
- Galactic Geochelone (Ubuntu 20.04 Focal) - EOL
- Eloquent Elusor (Ubuntu 18.04 Bionic) - EOL
- Dashing Diademata (Ubuntu 18.04 Bionic) - EOL
These are the ROS (1) supported Distributions:
Note: The latest ROS (1) release is version 2.3.2.
- Noetic Ninjemys (Ubuntu 20.04 Focal)
- Melodic Morenia (Ubuntu 18.04 Bionic)
- Kinetic Kame (Ubuntu 16.04 Xenial)
ROS Documentation and Installation instructions can be found at: https://docs.ros.org
Note: Check the ROS Release documentation at ROS official distributions
Note: Check https://www.intelrealsense.com/message-to-customers/ for supported cameras.
Getting Started
- ROS1 installation Instructions and distributions - link
- ROS2 installation Instructions and distributions - link
ROS Camera nodes examples
Link to Example | Experience level | Supported Cameras | Link to GitHub |
---|---|---|---|
D400, L500, T265 | |||
D400 | demo_pointcloud.launch | ||
D400 | |||
T265 | |||
D400, L500, T265 | |||
D400 | |||
D400+T265 | |||
D400+T265 | |||
D400+T265 | |||
D400 | |||
D400 |
Published Topics
The published topics differ according to the device and parameters.
See the table below for Topics supported according to SKUs.
For a full list of topics type 'rostopic list' with your camera connected.
D400 Stereo Depth Cameras
Feature | Topic | Camera Model |
---|---|---|
Color | /camera/color/camera_info | Applies to all D400 camera with RGB, ie: D415, D435, D435i, D455 *Note: /color refers to the stream coming out and /rgb_camera refers to the device itself |
Depth/Stereo | /camera/depth/camera_info | All D400 *Note: /depth refers to the stream coming out and /stereo_module refers to the device itself |
Extrinsics | /camera/extrinsics/depth_to_color | All D400 |
Left IR Imager | /camera/infra1/camera_info | All D400 |
Right IR Imager | /camera/infra2/camera_info | All D400 |
PointCloud | /camera/depth/color/points | All D400 |
IMU | /camera/motion_module/parameter_descriptions | Applies to all D400 cameras with IMU: D435i, D455 Notes: |
Other | /diagnostics | All D400 |
L500 Lidar Depth Cameras
Feature | Topic | Camera Model |
---|---|---|
Color | /camera/color/camera_info | L515 |
Depth | /camera/depth/camera_info | L515 |
IR Imager | /camera/infra/camera_info | L515 |
Extrinsics | /camera/extrinsics/depth_to_color | L515 |
PointCloud | /camera/depth/color/points | L515 |
IMU | /camera/motion_module/parameter_descriptions | L515 Notes: |
Other | /diagnostics | L515 |
T265 Tracking Camera
Feature | Topic | Camera Model |
---|---|---|
Odometry | /camera/odom/sample | T265 |
Tracking | /camera/tracking_module/parameter_descriptions | T265 |
Fisheye | /camera/fisheye1/camera_info | T265 |
IMU | /camera/gyro/imu_info | T265 |
Other | /diagnostics | T265 |
Compression packages
The compression packages apply to all the camera Modules (SKUs).
Feature | Topic | Comment |
---|---|---|
compressed-image-transport | /camera/color/image_raw/compressed | Requires compressed-image-transport package installed such as package ros-kinetic-compressed-image-transport |
compressed-depth-image-transport | /camera/color/image_raw/compressedDepth | Requires compressed-depth-image-transport package installed such as package ros-kinetic-theora-image-transport |
theora-image-transport | /camera/color/image_raw/theora | Requires theora-image-transport package installed such as package ros-kinetic-theora-image-transport |
Note: '/camera' prefix can be modified:
- The "/camera" prefix in the topics is the default parameter and can be changed - refer to tf_prefix parameter in the table below.
- rs_multiple_devices.launch demonstrates how to modify the /camera prefix for multiple cameras
Launch parameters
Parameter | Description | Default / Comment |
---|---|---|
serial_no | Attach to the device with the given serial number (serial_no) number. | Default: Attach to a randomly available RealSense device. |
usb_port_id | Attach to the device with the given USB port (usb_port_id). i.e 4-1, 4-2 etc. | Default: Ignore USB port when choosing a device. |
device_type | Attach to a device whose name includes the given device_type regular expression pattern. | Default: Ignore device type |
rosbag_filename | Publish topics from rosbag file | |
initial_reset | Allows resetting the device before using it. Recommended to be used for example, when a glitch prevented the device from being properly closed. | If set to true, the device will reset prior to usage. |
align_depth | If set to true, will publish additional topics with all the images aligned to the depth image. | The topics are of the form: /camera/aligned_depth_to_color/image_raw etc. |
filters | The options, separated by commas: colorizer, pointcloud, | The depth FOV and the texture FOV are not similar. By default, pointcloud is limited to the section of depth containing the texture. You can have a full depth to pointcloud, coloring the regions beyond the texture with zeros, by setting allow_no_texture_points to true. |
enable_sync | Gather closest frames of different sensors, infra red, color and depth, to be sent with the same timetag. | This happens automatically when filters such as pointcloud are enabled. |
<stream_type>_width, <stream_type>_height, <stream_type>_fps | <stream_type> can be any of infra, color, fisheye, depth, gyro, accel, pose. | Setting a value to 0, will choose the first format in the inner list. (i.e. consistent between runs but not defined). |
enable_<stream_name> | Choose whether to enable a specified stream or not. <stream_name> can be any of infra1, infra2, color, depth, fisheye, fisheye1, fisheye2, gyro, accel, pose. | Default is true. |
tf_prefix | This parameter allows changing the frames' IDs prefix per camera. | By default all frames' IDs have the same prefix - camera_. |
base_frame_id | Define the frame_id all static transformations refers to. | |
odom_frame_id | Define the origin coordinate system in ROS convention (X-Forward, Y-Left, Z-Up). | The rest of the frame IDs can be found at nodelet.launch.xml |
unite_imu_method | Cameras such as D435i, D455 and T265, have built in IMU components which produce 2 separate streams: gyro - which shows angular velocity and accel which shows linear acceleration. Each with it's own frequency. (See details in Note-2) | By default, 2 corresponding topics are available, each with only the relevant fields of the message sensor_msgs::Imu are filled out. |
clip_distance | Remove from the depth image all values above a given value (meters). | Disable by giving negative value (default) |
linear_accel_cov, angular_velocity_cov | Set the variance given to the Imu readings. | For the T265, these values are being modified by the inner confidence value. |
hold_back_imu_for_frames | Images processing takes time. Therefor there is a time gap between the moment the image arrives at the wrapper and the moment the image is published to the ROS environment. During this time, Imu messages keep on arriving which may result image with earlier timestamp to be published after Imu message with later timestamp. | Setting hold_back_imu_for_frames to true will hold the Imu messages back while processing the images and then publish them all in a burst, thus keeping the order of publication as the order of arrival. |
topic_odom_in | Applies to T265: add wheel odometry information through this topic. | The code refers only to the twist.linear field in the message. |
calib_odom_file | Applies to T265: include odometry input, it must be given a configuration file. | Explanations can be found here. The calibration is done in ROS coordinates system. |
publish_tf | A Boolean parameter, publish or not TF at all. | Default is True. |
tf_publish_rate | A double parameter, positive values mean dynamic transform publication with specified rate, all other values mean static transform publication. | Default is 0. |
publish_odom_tf | A Boolean parameter, publish if True TF from odom_frame to pose_frame. | Default is True. |
Notes:
(1) See detail description of filters at Post-processing filters
- colorizer: will color the depth image. On the depth topic an RGB image will be published, instead of the 16bit depth values.
- pointcloud: will add a pointcloud topic /camera/depth/color/points. The texture of the pointcloud can be modified in rqt_reconfigure (see below) or using the parameters: pointcloud_texture_stream and pointcloud_texture_index. Run 'rqt_reconfigure' to see available values for these parameters.
(2) Setting unite_imu_method creates a new topic, imu, that replaces the default gyro and accel topics. The imu topic is published at the rate of the gyro. All the fields of the Imu message under the imu topic are filled out.
- linear_interpolation: Every gyro message is attached by the accel message interpolated to the gyro's timestamp.
- copy: Every gyro message is attached by the last accel message.
Dynamic Reconfigure Parameters
The following command allow to change camera control values using [http://wiki.ros.org/rqt_reconfigure].
rosrun rqt_reconfigure rqt_reconfigure


Updated about 2 months ago