ROS 2 - ZED Stereo Node
ROS 2 - ZED Stereo Node
The easiest way to start a ZED ROS 2 node for a stereo camera is by using the command line:
where <camera model> must be replaced with one in the list zed, zedm, zed2, zed2i, zedx, zedxm, and virtual.
Published Topics
Not all the topics are advertised by default. The version v5.1.0 of the ROS 2 Wrapper introduces new parameters to enable/disable the publishing of each topic. Please refer to the “Configuration parameters” section for more details.
The ZED node publishes data to the following topics:
-
Status
~/status/health: the general status of the node (custom message).~/status/heartbeat: heartbeat signal to monitor if the node is alive from other nodes (custom message).
-
Image streams
The image topic names are created using the following naming convention:
~/<sensor_type>/<color_model>/<rect_type>/image
Starting from version 5.1.0 of the ROS 2 Wrapper the new convention replaces the previous formats such as ~/<sensor_type>/image_<rect_type>_<color_model> and ~/<sensor_type>_<rect_type>/image_<rect_type>_<color_model> (e.g., ~/left/image_rect_color, ~/rgb_raw/image_raw_gray). Please update your launch files and scripts to use the new topic names.
-
RGB channel
~/rgb/color/rect/image: Color rectified image.~/rgb/color/rect/camera_info: Color camera calibration data.~/rgb/gray/rect/image: Grayscale rectified image.~/rgb/gray/rect/camera_info: Grayscale camera calibration data.~/rgb/color/raw/image: Color unrectified image.~/rgb/color/raw/camera_info: Color raw calibration data.~/rgb/gray/raw/image: Grayscale unrectified image.~/rgb/gray/raw/camera_info: Grayscale raw calibration data.
-
Left channel
~/left/color/rect/image: Left sensor RGB rectified image.~/left/color/rect/camera_info: Left sensor RGB camera calibration data.~/left/gray/rect/image: Left sensor Grayscale rectified image.~/left/gray/rect/camera_info: Left sensor Grayscale camera calibration data.~/left/color/raw/image: Left sensor RGB unrectified image.~/left/color/raw/camera_info: Left sensor RGB raw calibration data.~/left/gray/raw/image: Left sensor Grayscale unrectified image.~/left/gray/raw/camera_info: Left sensor Grayscale raw calibration data.
-
Right channel
~/right/color/rect/image: Right sensor RGB rectified image.~/right/color/rect/camera_info: Right sensor RGB camera calibration data.~/right/gray/rect/image: Right sensor Grayscale rectified image.~/right/gray/rect/camera_info: Right sensor Grayscale camera calibration data.~/right/color/raw/image: Right sensor RGB unrectified image.~/right/color/raw/camera_info: Right sensor RGB raw calibration data.~/right/gray/raw/image: Right sensor Grayscale unrectified image.~/right/gray/raw/camera_info: Right sensor Grayscale raw calibration data.
The rgb and left channels of stereo cameras are identical. We use both names to differentiate the usage: while left and right are used for stereo processing, rgb is used to be associated to the synchronized depth map.
-
Stereo pair
~/stereo/color/rect/image: side-by-side left/right rectified stereo pair. Calibration data are available in the topics:~/left/color/rect/camera_infoand~/right/color/rect/camera_info.~/stereo/color/raw/image: side-by-side left/right unrectified stereo pair. Calibration data are available in the topics:~/left/color/raw/camera_infoand~/right/color/raw/camera_info.
-
Depth and point cloud
~/depth/camera_info: Depth camera calibration data.~/depth/depth_registered: Depth map image registered on left image.~/depth/depth_info: minimum and maximum depth information (custom message).~/point_cloud/cloud_registered: Registered color point cloud.~/confidence/confidence_map: Confidence image (doubleing point values).~/disparity/disparity_image: Disparity image.
-
Sensors data
~/left_cam_imu_transform: Transform from the left camera sensor to the IMU sensor.~/imu/data: Accelerometer, gyroscope, and orientation data in Earth frame.~/imu/data_raw: Accelerometer and gyroscope data in Earth frame.~/imu/mag: Raw magnetometer data (only ZED 2 and ZED 2i).~/atm_press: atmospheric pressure (only ZED 2 and ZED 2i).~/temperature/imu: temperature measured by the IMU sensor.~/temperature/left: temperature measured near the left CMOS sensor (only ZED 2 and ZED 2i).~/temperature/right: temperature measured near the right CMOS sensor (only ZED 2 and ZED 2i).
-
Positional tracking
~/pose: Absolute 3D position and orientation relative to the Map frame (Sensor Fusion algorithm + SLAM).~/pose/status: the status of the positional tracking module (custom message).~/pose_with_covariance: Camera pose referred to Map frame with covariance.~/odom: Absolute 3D position and orientation relative to the Odometry frame (pure visual odometry for ZED, visual-inertial odometry for ZED Mini).~/odom/status: the status of the odometry from the positional tracking module (custom message).~/path_map: Sequence of camera poses in Map frame.~/path_odom: Sequence of camera odometry poses in Map frame.
-
Geo Tracking
~/pose/filtered: the GNSS fused pose of the robot~/pose/filtered/status: the status of the GNSS fused pose (custom message).~/geo_pose/: the Latitude/Longitude pose of the robot~/geo_pose/status: the status of the Latitude/Longitude pose (custom message).
-
3D Mapping
~/mapping/fused_cloud: Fused point cloud created when theenable_mappingservice is called.
-
Object Detection
~/obj_det/objects: detected objects (custom message).
-
Body Tracking
~/body_trk/skeletons: detected body skeletons (custom message).
-
Plane Detection
~/plane: Detected plane (custom message).~/plane_marker: Detected plane object to be displayed on RVIZ 2.
Each topic has a common prefix created by the launch file as ~ = /<namespace>/<node_name>/, where <namespace> is replaced with the value of the parameter camera_name and <node_name> is the name of the node, e.g. zed_node.
Image Transport
The ROS 2 wrapper supports the stack image_transport introduced with ROS 2 Crystal Clemmys.
All the image topics are published using the image_transport::Publisher object, correctly associating the sensor_msgs::msg::CameraInfo message to the relative sensor_msg::msg::Image message and creates the relative compressed image streams.
We recommend using the standard available image transports:
raw: uncompressed imagecompressed: JPEG or PNG compressed imagetheora: Ogg Theora compressed imagecompressedDepth: depth image compressed with a lossless algorithm
For proper association between images and their corresponding camera information, the ZED ROS 2 Wrapper also publishes camera_info topics for all compressed image streams:
~/rgb/color/rect/image/camera_info~/rgb/gray/rect/image/camera_info~/rgb/color/raw/image/camera_info~/rgb/gray/raw/image/camera_info
The image transport topics are not advertised if NITROS is enabled. Please refer to the dedicated section about NVIDIA® Isaac ROS Nitros for more details.
NVIDIA® Isaac ROS Nitros
The ZED ROS 2 Wrapper supports the NVIDIA® Isaac™ ROS Nitros package for zero-copy transport of ROS messages using NVIDIA® GPUDirect® RDMA.
NVIDIA® Isaac ROS Nitros integration is enabled and used only if the required packages are manually installed. They are not added as a dependency because this is an optional feature.
For more information about the installation and usage of the NVIDIA® Isaac™ ROS packages, please refer to the dedicated section of the documentation: ZED Isaac™ ROS Integration Overview.
Point Cloud Transport
The ROS 2 wrapper supports the stack pointcloud_transport introduced with ROS 2 Humble Hawksbill.
The point cloud transport is enabled and used only if the required packages are manually installed, they are not added as a dependency because this is an optional feature:
Point cloud topics are published using the point_cloud_transport::Publisher object, which provides both standard raw and compressed point cloud streams for efficient data transmission.
QoS profiles
All the topics are configured by default to use the following ROS 2 QoS profile:
- Reliability: RELIABLE
- History (Depth): KEEP_LAST (10)
- Durability: VOLATILE
- Lifespan: Infinite
- Deadline: Infinite
- Liveliness: AUTOMATIC
- Liveliness lease duration: Infinite
Read the official ROS 2 documentation about the QoS and the relatived settings for details.
The QoS settings can be modified by changing the relative parameters in the YAML files, as described in this official ROS 2 design document.
When creating a subscriber, be sure to use a compatible QOS profile according to the following tables:
Compatibility of QoS durability profiles:
Compatibility of QoS reliability profiles:
In order for a connection to be made, all of the policies that affect compatibility must be compatible. For instance, if a publisher-subscriber pair has compatible reliability QoS profiles, but incompatible durability QoS profiles, the connection will not be made.
for a detailed list of all the compatibility settings, please refer to the official ROS 2 documentation.
Configuration parameters
Specify your launch parameters in the common_stereo.yaml, zed.yaml, zedm.yaml, zed2.yaml, zed2i.yaml, zedx.yaml, zedxm.yaml, and virtual files available in the folder zed_wrapper/config.
General parameters
Namespace: general
common_stereo.yaml
* Dynamic parameter
zed.yaml, zedm.yaml, zed2.yaml, zed2i.yaml, zedx.yaml, zedxm.yaml, and virtual.yaml
SVO input parameters
Namespace: svo
common_stereo.yaml
Streaming input parameters
Namespace: stream
common_stereo.yaml
Simulation input parameters
Namespace: simulation
common_stereo.yaml
Streaming server parameters
Namespace: stream_server
common_stereo.yaml
Video parameters
Namespace: video
common_stereo.yaml
* Dynamic parameter
zed.yaml, zed2.yaml, aand zed2i.yaml
* Dynamic parameter
zedx.yaml, zedxm.yaml, and virtual.yaml
* Dynamic parameter
Region of Interest parameters
Namespace: region_of_interest
common_stereo.yaml
Depth parameters
Namespace: depth
common_stereo.yaml
To disable depth calculation set quality to NONE. All the other parameters relative to depth will be ignored and only the video streams and sensors data will be published.
* Dynamic parameter
zed.yaml, zedm.yaml, zed2.yaml, zed2i.yaml, zedx.yaml, zedxm.yaml, and virtual.yaml
* Dynamic parameter
Positional tracking parameters (Odometry and Localization)
Namespace: pos_tracking
common_stereo.yaml
Global Localization (GNSS Fusion)
Namespace: gnss_fusion
common_stereo.yaml
Mapping parameters
Namespace: mapping
common_stereo.yaml
Sensors parameters
Namespace: sensors
common_stereo.yaml
Object detection parameters
Namespace: object_detection
common_stereo.yaml
object_detection.yaml
* Dynamic parameter
custom_object_detection.yaml
FOR EACH CLASS CREATE THE FOLLOWING PARAMETERS
* Dynamic parameter
Body Tracking parameters
Namespace: body_tracking
common_stereo.yaml
* Dynamic parameter
Body Tracking parameters
Namespace: body_tracking
common_stereo.yaml
Debug parameters
Namespace: debug
common_stereo.yaml
Dynamic parameters
The ZED node lets you reconfigure many parameters dynamically during the execution of the node. All the dynamic parameters are indicated with a * in the list above and with the tag [DYNAMIC] in the comments of the YAML files.
You can set the parameters using the CLI command ros2 param set, e.g.:
if the parameter is set successfully, you will get a confirmation message:
In the case you tried to set a parameter that’s not dynamically reconfigurable, or you specified an invalid value, you will get this type of error:
and the ZED node will report a warning message explaining the error type:
You can also use the Configuration -> Dynamic Reconfigure plugin of the rqt tool to dynamically set parameters by using a graphic interface.

Transform frames
The ZED ROS 2 wrapper broadcasts multiple coordinate frames that each provides information about the camera’s position and orientation. If needed, the reference frames can be changed in the launch file.
<camera_name>_camera_linkis the current position and orientation of the ZED base center. It corresponds to the bottom central fixing hole.<camera_name>_camera_centeris the current position and orientation of ZED middle baseline, determined by visual odometry and the tracking module.<camera_name>_right_camerais the position and orientation of the ZED’s right camera.<camera_name>_right_camera_opticalis the position and orientation of the ZED’s right camera optical frame.<camera_name>_left_camerais the position and orientation of the ZED’s left camera.<camera_name>_left_camera_opticalis the position and orientation of the ZED’s left camera optical frame.<camera_name>_imu_linkis the origin of the inertial data frame (not available with ZED).<camera_name>_mag_linkis the origin of the magnetometer frame (ZED2/ZED2i only).<camera_name>_baro_linkis the origin of the barometer frame (ZED2/ZED2i only).<camera_name>_temp_left_linkis the origin of the left temperature frame (ZED2/ZED2i only).<camera_name>_temp_right_linkis the origin of the right temperature frame (ZED2/ZED2i only).
For RVIZ 2 compatibilty, the root frame map_frame is called map.
The TF tree generated by the zed_wrapper reflects the standard descripted in REP105.
The odometry frame is updated using only the “visual inertial odometry” information (loop closure is not applied).
The map frame is updated using the Positional Tracking algorithm provided by the StereoLabs SDK, fusing the inertial information from the IMU sensor, and applying loop closure information.
When the Geo Tracking module is enabled the ZED Node TF Tree reflects the following diagram:

Services
The ZED node provides the following services:
~/reset_odometry: Resets the odometry values eliminating the drift due to the Visual Odometry algorithm. The new odometry value is set to the latest camera pose received from the tracking algorithm.~/reset_pos_tracking: Restarts the Tracking algorithm setting the initial pose to the value available in the param server or to the latest pose set with the serviceset_pose.~/set_pose: Restarts the Tracking algorithm setting the initial pose of the camera to the value passed as vector parameter -> [X, Y, Z, R, P, Y]~/enable_obj_det: enable/disable object detection.~/enable_body_trk: enable/disable body tracking.~/enable_mapping: enable/disable spatial mapping.~/enable_streaming: enable/disable a local streaming server.~/start_svo_rec: Start recording an SVO file. If no filename is provided the default zed.svo is used. If no path is provided with the filename the default recording folder is ~/.ros/~/stop_svo_rec: Stop an active SVO recording.~/toggle_svo_pause: set/reset SVO playing pause. Note: Only available ifgeneral.svo_realtimeis false and if an SVO as been chosen as input source.~/set_svo_frame: Set the SVO playback frame to the specified value.~/set_roi: Set the Region of Interest to the described polygon.~/reset_roi: Reset the Region of Interest to the full image frame.~/toLL: converts frommapcoordinate frame to Latitude/Longitude Note: Only available if GNSS fusion is enabled~/fromLL: converts from Latitude/Longitude tomapcoordinate frame Note: Only available if GNSS fusion is enabled
Services can be called using the rqt graphical tool by enabling the plugin Plugins -> Services -> Service caller.
It is possible to call a service also by using the CLI command ros2 service call.
For example to start Object Detection for the ZED2 camera:
and the service server will reply:
Assigning a GPU to a camera
To improve performance, you can specify the gpu_id of the graphic card that will be used for the depth computation in the common_stereo.yaml configuration file. The default value (-1) will select the GPU with the highest number of CUDA cores. When using multiple ZEDs, you can assign each camera to a GPU to increase performance.
Node Diagnostic
The ZED ROS 2 node publishes useful diagnostic information aggregated into the /diagnostics topic using the diagnostic_updater package.
Diagnostic information can be analyzed and parsed by using ROS 2 tools, like for example the Runtime Monitor plugin of rqt.
Available information:
- Uptime
- Grab frequency and processing time
- Frame drop rate
- Input mode
- Video and Depth publishing rate and processing time
- Depth Mode
- Point Cloud publishing rate and processing time
- GNSS Fusion status
- Odometry and Localization status
- TF broadcasting rate
- Object Detection status and publishing rate
- Body Tracking status and publishing rate
- IMU TF broadcasting rate
- Sensor data publishing rate
- Camera Internal temperatures
- SVO playback status
- SVO recording status
- Streaming server status


