The ROS Wrapper for Intel® RealSense™ cameras allows you to use Intel® RealSense™ cameras with ROS2.

The ROS Wrapper for Intel® RealSense™ cameras releases (latest and previous versions), can be found at ROS Wrapper for Intel® RealSense™ cameras releases

The full readme of the ROS Wrapper for Intel® RealSense™ cameras can be found here: README.md

These are the ROS2 supported Distributions:

  • Rolling Ridley (Ubuntu 24.04 Noble Numbat) - in Development phase
  • Jazzy Jalisco (Ubuntu 24.04 Noble Numbat) - in Development phase - LTS
  • Iron Irwini (Ubuntu 22.04 Jammy Jellyfish)
  • Humble Hawksbill (Ubuntu 22.04 Jammy Jellyfish) - LTS

ROS2 Documentation and Installation instructions can be found at: https://docs.ros.org/en/rolling/index.html

📌 Note: Check the ROS2 Releases documentation at ROS2 Official Releases
📌 Note: Check Messages to customers section for supported cameras.

Getting Started

ROS2 installation Instructions and distributions - link

ROS2 Camera nodes examples

Camera namespace and camera name

User can set the camera name and camera namespace, to distinguish between cameras and platforms, which helps identifying the right nodes and topics to work with.

Example

If user have multiple cameras (might be of the same model) and multiple robots then user can choose to launch/run his nodes on this way. For the first robot and first camera he will run/launch it with these parameters: ros2 launch realsense2_camera rs_launch.py camera_namespace:=robot1 camera_name:=D455_1 or ros2 run realsense2_camera realsense2_camera_node --ros-args -r __node:=D455_1 -r __ns:=robot1

Result:

> ros2 node list
/robot1/D455_1

> ros2 topic list
/robot1/D455_1/color/camera_info
/robot1/D455_1/color/image_raw
/robot1/D455_1/color/metadata
/robot1/D455_1/depth/camera_info
/robot1/D455_1/depth/image_rect_raw
/robot1/D455_1/depth/metadata
/robot1/D455_1/extrinsics/depth_to_color
/robot1/D455_1/imu

> ros2 service list
/robot1/D455_1/device_info

Default behavior

If non of these parameters are given, the default values will be camera_namespace:=camera and camera_name:=camera and the result is the same as in the Published Topics section below.

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 ros2 topic list after launching the camera node.

D400 Stereo Depth Cameras

FeatureTopicCamera Model
Color (RGB Module)/camera/camera/color/camera_info
/camera/camera/color/image_raw
/camera/camera/color/metadata
Applies to all D400 camera with RGB, ie: D405, D415, D435, D435i, D455, D457

*Note: /color refers to the stream coming out and /rgb_camera refers to the device itself
Depth (Stero Module)/camera/camera/depth/camera_info
/camera/camera/depth/image_rect_raw
/camera/camera/depth/metadata
All D400

*Note: /depth refers to the stream coming out and /stereo_module refers to the device itself
Extrinsics/camera/camera/extrinsics/depth_to_color
/camera/camera/extrinsics/depth_to_infra1
/camera/camera/extrinsics/depth_to_infra2
/camera/camera/extrinsics/depth_to_accel
/camera/camera/extrinsics/depth_to_gyro
All D400
after enabling color/infra1/infra2
Left IR Imager/camera/camera/infra1/camera_info
/camera/camera/infra1/image_rect_raw
All D400
after enabling infra1
Right IR Imager/camera/camera/infra2/camera_info
/camera/camera/infra2/image_rect_raw
All D400
after enabling infra2
PointCloud/camera/camera/depth/color/pointsAll D400
after enabling pointcloud
Aligned Streams/camera/camera/aligned_depth_to_color/camera_info
/camera/camera/aligned_depth_to_color/image_raw
All D400, after enabling align_depth filter
IMU/camera/camera/gyro/imu_info
/camera/camera/gyro/metadata
/camera/camera/gyro/sample
/camera/camera/accel/imu_info
/camera/camera/accel/metadata
/camera/camera/accel/sample
/camera/camera/imu
Applies to all D400 cameras with IMU: D435i, D455

Notes:
_After setting parameter unite_imu_method new topic are published /camera/imu
Other/diagnostics
/tf
/tf_static
All D400

Compression packages

The compression packages apply to all the camera Modules (SKUs). To enable compressed topics, user should install image-transport-plugin package (For example, for humble distro run this command for installation sudo apt install ros-humble-image-transport)

FeatureTopicComment
compressed-image-transport/camera/camera/color/image_raw/compressed
/camera/camera/color/image_raw/compressed/parameter_descriptions
/camera/camera/color/image_raw/compressed/parameter_updates
/camera/camera/depth/image_rect_raw/compressed
/camera/camera/depth/image_rect_raw/compressed/parameter_descriptions
/camera/camera/depth/image_rect_raw/compressed/parameter_updates
/camera/camera/infra1/image_rect_raw/compressed
/camera/camera/infra1/image_rect_raw/compressed/parameter_descriptions
/camera/camera/infra1/image_rect_raw/compressed/parameter_updates
/camera/camera/infra2/image_rect_raw/compressed
/camera/camera/infra2/image_rect_raw/compressed/parameter_descriptions
/camera/camera/infra2/image_rect_raw/compressed/parameter_updates
Requires compressed-image-transport package installed such as package ros-kinetic-compressed-image-transport
compressed-depth-image-transport/camera/camera/color/image_raw/compressedDepth
/camera/camera/color/image_raw/compressedDepth/parameter_descriptions
/camera/camera/color/image_raw/compressedDepth/parameter_updates
/camera/camera/depth/image_rect_raw/compressedDepth
/camera/camera/depth/image_rect_raw/compressedDepth/parameter_descriptions
/camera/camera/depth/image_rect_raw/compressedDepth/parameter_updates
/camera/camera/infra1/image_raw/compressedDepth
/camera/camera/infra1/image_raw/compressedDepth/parameter_descriptions
/camera/camera/infra1/image_raw/compressedDepth/parameter_updates
/camera/camera/infra2/image_rect_raw/compressedDepth
/camera/camera/infra2/image_rect_raw/compressedDepth/parameter_descriptions
/camera/camera/infra2/image_rect_raw/compressedDepth/parameter_updates
Requires compressed-depth-image-transport package installed such as package ros-kinetic-compressed-depth-image-transport
theora-image-transport/camera/camera/color/image_raw/theora
/camera/camera/color/image_raw/theora/parameter_descriptions
/camera/camera/color/image_raw/theora/parameter_updates
/camera/camera/depth/image_rect_raw/theora
/camera/camera/depth/image_rect_raw/theora/parameter_descriptions
/camera/camera/depth/image_rect_raw/theora/parameter_updates
Requires theora-image-transport package installed such as package ros-kinetic-theora-image-transport

Launch parameters

  • For the entire list of parameters type ros2 param list.

  • For reading a parameter value use ros2 param get <node> <parameter_name>

    • For example: ros2 param get /camera/camera depth_module.emitter_enabled
  • For setting a new value for a parameter use ros2 param set <node> <parameter_name> <value>

    • For example: ros2 param set /camera/camera depth_module.emitter_enabled 1

    Parameters that can be modified during runtime:

    • All of the filters and sensors inner parameters.
    • Video Sensor Parameters: (depth_module and rgb_camera)
      • They have, at least, the profile parameter.
        • The profile parameter is a string of the following format: <width>X<height>X<fps> (The dividing character can be X, x or ",". Spaces are ignored.)
        • For example: depth_module.profile:=640x480x30 rgb_camera.profile:=1280x720x30
        • Since infra, infra1, infra2 and depth are all streams of the depth_module, their width, height and fps are defined by the same param depth_module.profile
        • If the specified combination of parameters is not available by the device, the default or previously set configuration will be used.
          • Run ros2 param describe <your_node_name> <param_name> to get the list of supported profiles.
        • Note: Should re-enable the stream for the change to take effect.
      • _<stream_name>__format
        • This parameter is a string used to select the stream format.
        • <streamname> can be any of _infra, infra1, infra2, color, depth.
        • For example: depth_module.depth_format:=Z16 depth_module.infra1_format:=y8 rgb_camera.color_format:=RGB8
        • This parameter supports both lower case and upper case letters.
        • If the specified parameter is not available by the stream, the default or previously set configuration will be used.
          • Run ros2 param describe <your_node_name> <param_name> to get the list of supported formats.
        • Note: Should re-enable the stream for the change to take effect.
      • If the stream doesn't support the user selected profile <width>X<height>X<fps> + <format>, it will not be opened and a warning message will be shown.
        • Should update the profile settings and re-enable the stream for the change to take effect.
        • Run rs-enumerate-devices command to know the list of profiles supported by the connected sensors.
    • enable_<stream_name>:
      • Choose whether to enable a specified stream or not. Default is true for images and false for orientation streams.
      • <streamname> can be any of _infra, infra1, infra2, color, depth, gyro, accel.
      • For example: enable_infra1:=true enable_color:=false
    • enable_sync:
      • gathers closest frames of different sensors, infra red, color and depth, to be sent with the same timetag.
      • This happens automatically when such filters as pointcloud are enabled.
    • _<stream_type>__qos:
      • Sets the QoS by which the topic is published.
      • <streamtype> can be any of _infra, infra1, infra2, color, depth, gyro, accel.
      • Available values are the following strings: SYSTEM_DEFAULT, DEFAULT, PARAMETER_EVENTS, SERVICES_DEFAULT, PARAMETERS, SENSOR_DATA.
      • For example: depth_qos:=SENSOR_DATA
      • Reference: ROS2 QoS profiles formal documentation
    • Notice: _<stream_type>__info_qos refers to both camera_info topics and metadata topics.
    • tf_publish_rate:
      • double, rate (in Hz) at which dynamic transforms are published
      • Default value is 0.0 Hz (means no dynamic TF)
      • This param also depends on publish_tf param
        • If publish_tf:=false, then no TFs will be published, even if tf_publish_rate is >0.0 Hz
        • If publish_tf:=true and tf_publish_rate set to >0.0 Hz, then dynamic TFs will be published at the specified rate
    • unite_imu_method:
      • For the D400 cameras with built in IMU components, below 2 unrelated streams (each with it's own frequency) will be created:
        • gyro - which shows angular velocity
        • accel - which shows linear acceleration.
      • Both streams will publish data to its corresponding topics:
        • '/camera/camera/gyro/sample' & '/camera/camera/accel/sample'
        • Though both topics are of same message type 'sensor_msgs::Imu', only their relevant fields are filled out.
      • A new topic called imu will be created, when both accel and gyro streams are enabled and the param unite_imu_method set to > 0.
        • Data from both accel and gyro are combined and published to this topic
        • All the fields of the Imu message are filled out.
        • It will be published at the rate of the gyro.
      • unite_imu_method param supports below values:
        • 0 -> none: no imu topic
        • 1 -> copy: Every gyro message will be attached by the last accel message.
        • 2 -> linear_interpolation: Every gyro message will be attached by an accel message which is interpolated to gyro's timestamp.
      • Note: When the param unite_imu_method is dynamically updated, re-enable either gyro or accel stream for the change to take effect.

    Parameters that cannot be changed in runtime:

    • serial_no:
      • will attach to the device with the given serial number (serial_no) number.
      • Default, attach to the first (in an inner list) RealSense device.
      • Note: serial number should be defined with "_" prefix.
        • That is a workaround until a better method will be found to ROS2's auto conversion of strings containing only digits into integers.
      • Example: serial number 831612073525 can be set in command line as serial_no:=_831612073525.
    • usb_port_id:
      • will attach to the device with the given USB port (usb_port_id).
      • For example: usb_port_id:=4-1 or usb_port_id:=4-2
      • Default, ignore USB port when choosing a device.
    • device_type:
      • will attach to a device whose name includes the given device_type regular expression pattern.
      • Default, ignore device type.
      • For example:
        • device_type:=d435 will match d435 and d435i.
        • device_type=d435(?!i) will match d435 but not d435i.
    • reconnect_timeout:
      • When the driver cannot connect to the device try to reconnect after this timeout (in seconds).
      • For Example: reconnect_timeout:=10
    • wait_for_device_timeout:
      • If the specified device is not found, will wait wait_for_device_timeout seconds before exits.
      • Defualt, wait_for_device_timeout < 0, will wait indefinitely.
      • For example: wait_for_device_timeout:=60
    • rosbag_filename:
      • Publish topics from rosbag file. There are two ways for loading rosbag file:
      • Command line - ros2 run realsense2_camera realsense2_camera_node -p rosbag_filename:="/full/path/to/rosbag.bag"
      • Launch file - set rosbag_filename parameter with rosbag full path (see realsense2_camera/launch/rs_launch.py as reference)
    • initial_reset:
      • On occasions the device was not closed properly and due to firmware issues needs to reset.
      • If set to true, the device will reset prior to usage.
      • For example: initial_reset:=true
    • base_frame_id: defines the frame_id all static transformations refers to.
    • clip_distance:
      • Remove from the depth image all values above a given value (meters). Disable by giving negative value (default)
      • For example: clip_distance:=1.5
    • linear_accel_cov, angular_velocity_cov: sets the variance given to the Imu readings.
    • 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 and a situation is created where an image with earlier timestamp is published after Imu message with later timestamp. If that is a problem, 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. Note that in either case, the timestamp in each message's header reflects the time of it's origin.
    • publish_tf:
      • boolean, enable/disable publishing static and dynamic TFs
      • Defaults to True
        • So, static TFs will be published by default
        • If dynamic TFs are needed, user should set the param tf_publish_rate to >0.0 Hz
      • If set to false, both static and dynamic TFs won't be published, even if the param tf_publish_rate is set to >0.0 Hz
    • diagnostics_period:
      • double, positive values set the period between diagnostics updates on the /diagnostics topic.
      • 0 or negative values mean no diagnostics topic is published. Defaults to 0.

        The /diagnostics topic includes information regarding the device temperatures and actual frequency of the enabled streams.

📘

Notes:

(1) See detail description of filters at Post-processing filters

Each of the below filters have it's own parameters, following the naming convention of <filter_name>.<parameter_name> including a <filter_name>.enable parameter to enable/disable it.

The following post processing filters are available:

  • align_depth: If enabled, will publish the depth image aligned to the color image on the topic /camera/camera/aligned_depth_to_color/image_raw.

    • The pointcloud, if created, will be based on the aligned depth image.
  • 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/camera/depth/color/points.

    • The texture of the pointcloud can be modified using the pointcloud.stream_filter parameter.
    • 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 pointcloud.allow_no_texture_points to true.
    • pointcloud is of an unordered format by default. This can be changed by setting pointcloud.ordered_pc to true.
  • hdr_merge: Allows depth image to be created by merging the information from 2 consecutive frames, taken with different exposure and gain values.

  • The way to set exposure and gain values for each sequence in runtime is by first selecting the sequence id, using the depth_module.sequence_id parameter and then modifying the depth_module.gain, and depth_module.exposure.

  • To view the effect on the infrared image for each sequence id use the filter_by_sequence_id.sequence_id parameter.

  • To initialize these parameters in start time use the following parameters:

    • depth_module.exposure.1
    • depth_module.gain.1
    • depth_module.exposure.2
    • depth_module.gain.2
  • For in-depth review of the subject please read the accompanying white paper.

  • The following filters have detailed descriptions in : https://github.com/IntelRealSense/librealsense/blob/master/doc/post-processing-filters.md

    • disparity_filter - convert depth to disparity before applying other filters and back.
    • spatial_filter - filter the depth image spatially.
    • temporal_filter - filter the depth image temporally.
    • hole_filling_filter - apply hole-filling filter.
    • decimation_filter - reduces depth scene complexity.

RGBD Topic

RGBD is a new topic, publishing [RGB + Depth] in the same message (see RGBD.msg for reference). For now, works only with depth aligned to color images, as color and depth images are synchronized by frame time tag.

These boolean paramters should be true to enable rgbd messages:

  • enable_rgbd: new paramter, to enable/disable rgbd topic, changeable during runtime
  • align_depth.enable: align depth images to rgb images
  • enable_sync: let librealsense sync between frames, and get the frameset with color and depth images combined
  • enable_color + enable_depth: enable both color and depth sensors

The current QoS of the topic itself, is the same as Depth and Color streams (SYSTEM_DEFAULT)

Example:

ros2 launch realsense2_camera rs_launch.py enable_rgbd:=true enable_sync:=true align_depth.enable:=true enable_color:=true enable_depth:=true 

Metadata topic

The metadata messages store the camera's available metadata in a json format. To learn more, a dedicated script for echoing a metadata topic in runtime is attached. For instance, use the following command to echo the camera/depth/metadata topic:

python3 src/realsense-ros/realsense2_camera/scripts/echo_metadada.py /camera/camera/depth/metadata

Available services

  • device_info : retrieve information about the device - serial_number, firmware_version etc. Type ros2 interface show realsense2_camera_msgs/srv/DeviceInfo for the full list. Call example: ros2 service call /camera/camera/device_info realsense2_camera_msgs/srv/DeviceInfo

Efficient intra-process communication

Our ROS2 Wrapper node supports zero-copy communications if loaded in the same process as a subscriber node. This can reduce copy times on image/pointcloud topics, especially with big frame resolutions and high FPS.

You will need to launch a component container and launch our node as a component together with other component nodes. Further details on "Composing multiple nodes in a single process" can be found here.

Further details on efficient intra-process communication can be found here.

Example

Manually loading multiple components into the same process

  • Start the component:

    ros2 run rclcpp_components component_container
    
  • Add the wrapper:

    ros2 component load /ComponentManager realsense2_camera realsense2_camera::RealSenseNodeFactory -e use_intra_process_comms:=true
    

    Load other component nodes (consumers of the wrapper topics) in the same way.

Limitations

  • Node components are currently not supported on RCLPY
  • Compressed images using image_transport will be disabled as this isn't supported with intra-process communication

Latency test tool and launch file

For getting a sense of the latency reduction, a frame latency reporter tool is available via a launch file.
The launch file loads the wrapper and a frame latency reporter tool component into a single container (so the same process).
The tool prints out the frame latency (now - frame.timestamp) per frame.

The tool is not built unless asked for. Turn on BUILD_TOOLS during build to have it available:

colcon build --cmake-args '-DBUILD_TOOLS=ON'

The launch file accepts a parameter, intra_process_comms, controlling whether zero-copy is turned on or not. Default is on:

ros2 launch realsense2_camera rs_intra_process_demo_launch.py intra_process_comms:=true