ROS 2 - ZED Node

The easiest way to start a ZED ROS2 node is by using the command line:

ZED:

$ ros2 launch zed_wrapper zed.launch.py

ZED Mini:

$ ros2 launch zed_wrapper zedm.launch.py

ZED 2:

$ ros2 launch zed_wrapper zed2.launch.py

ZED 2i:

$ ros2 launch zed_wrapper zed2i.launch.py

Published Topics

The ZED node publishes data to the following topics:

  • Left camera

    • ~/left/camera_info: Left camera calibration data.
    • ~/left/image_rect_color: Left camera color rectified image.
    • ~/left/image_rect_gray: Left camera gray rectified image.
    • ~/left_raw/camera_info: Left camera raw calibration data.
    • ~/left_raw/image_rect_color: Left camera color unrectified image.
    • ~/left_raw/image_rect_gray: Left camera gray unrectified image.
    • ~/rgb/camera_info: RGB calibration data.
    • ~/rgb/image_rect_color: RGB color rectified image.
    • ~/rgb/image_rect_gray: RGB gray rectified image.
    • ~/rgb_raw/camera_info: RGB raw calibration data.
    • ~/rgb_raw/image_rect_color: RGB color unrectified image.
    • ~/rgb_raw/image_rect_gray: RGB gray unrectified image.
  • Right camera

    • ~/right/camera_info: Right camera calibration data.
    • ~/right/image_rect_color: Right camera color rectified image.
    • ~/right/image_rect_gray: Right camera gray rectified image.
    • ~/right_raw/camera_info: Right camera raw calibration data.
    • ~/right_raw/image_rect_color: Right camera color unrectified image.
    • ~/right_raw/image_rect_gray: Right camera gray unrectified image.
  • Stereo pair

    • ~/stereo/image_rect_color: side-by-side left/right rectified stereo pair. Calibration data are available in the topics: ~/left/camera_info and ~/right/camera_info.
    • ~/stereo_raw/image_raw_color: side-by-side left/right unrectified stereo pair. Calibration data are available in the topics: ~/left_raw/camera_info and ~/right_raw/camera_info.
  • Depth and point cloud

    • ~/depth/camera_info: Depth camera calibration data.
    • ~/depth/depth_registered: Depth map image registered on left image.
    • ~/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 ZED2).
    • ~/atm_press: atmospheric pressure (only ZED2).
    • ~/temperature/imu: temperature measured by the IMU sensor.
    • ~/temperature/left: temperature measured near the left CMOS sensor.
    • ~/temperature/right: temperature measured near the right CMOS sensor.
  • Positional tracking

    • ~/pose: Absolute 3D position and orientation relative to the Map frame (Sensor Fusion algorithm + SLAM).
    • ~/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-M).
    • ~/path_map: Sequence of camera poses in Map frame.
    • ~/path_odom: Sequence of camera odometry poses in Map frame.
  • Mapping

    • ~/mapping/fused_cloud: Fused point cloud created when the enable_mapping service is called.
  • Object Detection

    • ~/obj_det/objects: Objects detected frame by frame when the enable_obj_det service is called.
  • Plane Detection

    • ~/plane: Detected plane.
    • ~/plane_marker: Detected plane object to be displayed on RVIZ2.

Note: 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 ROS2 wrapper supports the stack image_transport introduced with ROS2 Crystal Clemmys.

All the image topics are published using the image_transport::CameraPublisher object, that correctly associates the sensor_msgs::msg::CameraInfo message to the relative sensor_msg::msg::Image message and creates the relative compressed image streams.

Note: There are known issues with image_transport and ROS2 Foxy, read here for more information.

QoS profiles

All the topics are configured by default to use the following ROS2 QoS profile:

  • History: KEEP_LAST
  • Depth: 1
  • Reliability: RELIABLE
  • Durability: VOLATILE

The QoS settings can be modified by changing the relative parameters in the YAML files, as described below.

When creating a subscriber, be sure to use a compatible QOS profile according to the following tables:

Compatibility of QoS durability profiles:

Publisher Subscriber Connection Result
Volatile Volatile Yes Volatile
Volatile Transient local No -
Transient local Volatile Yes Volatile
Transient local Transient local Yes Transient local

Compatibility of QoS reliability profiles:

Publisher Subscriber Connection Result
Best effort Best effort Yes Best effort
Best effort Reliable No -
Reliable Best effort Yes Best effort
Reliable Reliable Yes Reliable

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.

Configuration parameters

Specify your launch parameters in the common.yaml, zed.yaml, zedm.yaml, zed2.yaml, and zed2i.yaml files available in the folder zed_wrapper/config.

General parameters

Namespace: general

common.yaml

Parameter Description Value
svo_file Specify SVO filename string, Note: relative file paths are not allowed
svo_loop Restart the SVO if the end of the file is reached true, false
svo_realtime if true SVO will be played trying to respect the original framerate eventually skipping frames, otherwise every frame will be processed respecting the pub_frame_rate setting true, false
camera_timeout_sec Camera timeout (sec) if communication fails int
camera_max_reconnect Reconnection temptatives after timeout, before shutting down int
camera_flip Flip the camera data if it is mounted upsidedown true, false
zed_id Select a ZED camera by its ID. IDs are assigned by Ubuntu. Useful when multiple cameras are connected. ID is ignored if an SVO path is specified int, default 0
serial_number Select a ZED camera by its Serial Number int
resolution Set the ZED camera resolution 0: HD2K, 1: HD1080, 2: HD720, 3: VGA
sdk_verbose Enable/disable the verbosity of the SDK int
grab_frame_rate Set ZED camera grab framerate int
pub_frame_rate* Set the video/depth publish rate double
gpu_id Select a GPU device for depth computation int
region_of_interest A polygon defining the ROI where the ZED SDK perform the processing ignoring the rest. Coordinates must be normalized to ‘1.0’ to be resolution independent. string (e.g. "[[0.5,0.25],[0.75,0.5],[0.5,0.75],[0.25,0.5]]")

* Dynamic parameter

zed.yaml, zedm.yaml, zed2.yaml, and zed2.yaml

Parameter Description Value
camera_model Type of Stereolabs camera string, zed, zedm, zed2, zed2i
camera_name User name for the camera, can be different from camera model string

Debug parameters

Namespace: debug

common.yaml

Parameter Description Value
debug_mode Enable general debug log outputs true, false
debug_sensors Enable sensors debug log outputs true, false

Video parameters

Namespace: video

common.yaml

Parameter Description Value
extrinsic_in_camera_frame if false extrinsic parameter in camera_info will use ROS native frame (X FORWARD, Z UP) instead of the camera frame (Z FORWARD, Y DOWN) [true use old behavior as for version < v3.1] true, false
img_downsample_factor Resample factor for image data matrices. The SDK works with native data sizes, but publishes rescaled matrices double, [0.01,1.0]
brightness* Image brightness int, [0,8]
contrast* Image contrast int, [0,8]
hue* Image hue int, [0,11]
saturation* Image saturation int, [0,8]
sharpness* Image sharpness int, [0,8]
gamma* Image gamma int, [0,8]
auto_exposure_gain* Enable the auto exposure and auto gain true, false
exposure* Exposure value if auto-exposure is false int [0,100]
gain* Gain value if auto-exposure is false int [0,100]
auto_whitebalance* Enable the auto white balance true, false
whitebalance_temperature* White balance temperature int [28,65]
qos_history How to queue messages 0: KEEP_LAST - 1: KEEP_ALL
qos_depth Size of the queue if KEEP_LAST int
qos_reliability Enable resending of not delivered message, if RELIABLE 0: BEST_EFFORT - 1: RELIABLE
qos_durability Enable storing of unread message if TRANSIENT_LOCAL 0: TRANSIENT_LOCAL - 1: VOLATILE

* Dynamic parameter

Depth parameters

Namespace: depth

common.yaml

Parameter Description Value
quality Select depth map quality 0: NONE, 1: PERFORMANCE, 2: QUALITY, 3: ULTRA, 4: NEURAL
sensing_mode Select depth sensing mode 0: STANDARD, 1: FILL
depth_stabilization Enable depth stabilization. Stabilizing the depth requires an additional computation load as it enables tracking true, false
openni_depth_mode Enable/disable the depth OpenNI format (16 bit, millimeters) int, [0,1]
depth_downsample_factor Resample factor for depth data matrices. The SDK works with native data sizes, but publishes rescaled matrices double, [0.01,1.0]
point_cloud_freq* frequency of the pointcloud publishing (equal or less to grab_frame_rate value) double
depth_confidence* Depth confidence threshold (lower values = more filtering) int [0,100]
depth_texture_conf* Depth tectureconfidence threshold (lower values = more filtering) int [0,100]
remove_saturated_areas* If true color saturated areas are not included in the depth map true, false
qos_history How to queue messages 0: KEEP_LAST - 1: KEEP_ALL
qos_depth Size of the queue if KEEP_LAST int
qos_reliability Enable resending of not delivered message, if RELIABLE 0: BEST_EFFORT - 1: RELIABLE
qos_durability Enable storing of unread message if TRANSIENT_LOCAL 0: TRANSIENT_LOCAL - 1: VOLATILE

Note: 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 (if using a ZED-M, ZED2 or ZED2i) will be available

* Dynamic parameter

zed.yaml, zedm.yaml and zed2.yaml

Parameter Description Value
min_depth Minimum depth value (from the camera) that will be computed double
max_depth Maximum range allowed for depth. Values beyond this limit will be reported as TOO_FAR double, ]0.0,20.0]

* Dynamic parameter

Positional tracking parameters

Namespace: pos_tracking

common.yaml

Parameter Description Value
pos_tracking_enabled Enable positional tracking when the node starts true, false
imu_fusion Enable IMU fusion. When set to false, only the optical odometry will be used. true, false
publish_tf Enable publishing of transform odom -> base_link and all the other transforms true, false
publish_map_tf Enable publishing of transform map -> odom. Only valid if publish_tf is true true, false
publish_imu_tf Enable publishing of transform imu_link -> left_camera_frame. true, false
base_frame Frame_id of the base frame string
map_frame Frame_id of the pose message string
odometry_frame Frame_id of the odom message string
area_memory_db_path The full path of the space memory DB string
area_memory Enable Loop Closing algorithm true, false
depth_min_range Set this value for removing fixed zones of the robot in the FoV of the camerafrom the visual odometry evaluation double
set_gravity_as_origin If ‘true’ align the positional tracking world to imu gravity measurement. Keep the yaw from the user initial pose. true, false
floor_alignment Indicates if the floor must be used as origin for height measures true, false
initial_base_pose Initial reference pose. Useful if the base_link does not start from the origin array
init_odom_with_first_valid_pose Inizitialized odometry from the first valid pose, not from the origin true, false
path_pub_rate Frequency (Hz) of publishing of the path messages double
path_max_count Maximum number of poses kept in the pose arrays (-1 for infinite) int
two_d_mode Enable if robot moves on a planar surface. Forces Z to fixed_z_value, roll and pitch to zero true, false
fixed_z_value Fixed value assigned to Z coordinate if two_d_mode is true double
transform_time_offset The value added to the timestamp of map->odom and odom->base_link transform being generated double
qos_history How to queue messages 0: KEEP_LAST - 1: KEEP_ALL
qos_depth Size of the queue if KEEP_LAST int
qos_reliability Enable resending of not delivered message, if RELIABLE 0: BEST_EFFORT - 1: RELIABLE
qos_durability Enable storing of unread message if TRANSIENT_LOCAL 0: TRANSIENT_LOCAL - 1: VOLATILE

Sensors parameters

Namespace: sensors

common.yaml

Parameter Description Value
sensors_image_sync Synchronize Sensors messages with latest published video/depth message true, false
sensors_pub_rate: Frequency of publishing of sensors data. MAX: 400. - MIN: grab rate double
qos_history How to queue messages 0: KEEP_LAST - 1: KEEP_ALL
qos_depth Size of the queue if KEEP_LAST int
qos_reliability Enable resending of not delivered message, if RELIABLE 0: BEST_EFFORT - 1: RELIABLE
qos_durability Enable storing of unread message if TRANSIENT_LOCAL 0: TRANSIENT_LOCAL - 1: VOLATILE

Object detection parameters (ZED2/ZED2i only)

Namespace: object_detection

common.yaml

Parameter Description Value
od_enabled Automatically enables Object Detection when the node starts true, false
confidence_threshold* Minimum confidence for an object to be added to the detected list double [0,100]
prediction_timeout During this time [sec], the object will have OK state even if it is not detected. Set this parameter to 0 to disable SDK predictions double
model Detection model ‘0’: MULTI_CLASS_BOX - ‘1’: MULTI_CLASS_BOX_MEDIUM - ‘2’: MULTI_CLASS_BOX_ACCURATE - ‘3’: HUMAN_BODY_FAST - ‘4’: HUMAN_BODY_MEDIUM - ‘5’: HUMAN_BODY_ACCURATE - ‘6’: PERSON_HEAD_BOX - ‘7’: PERSON_HEAD_BOX_ACCURATE
mc_people* Enable people detection for MULTI_CLASS_BOX and MULTI_CLASS_BOX_ACCURATE models true, false
mc_vehicle* Enable vehicles detection for MULTI_CLASS_BOX and MULTI_CLASS_BOX_ACCURATE models true, false
mc_bag* Enable bags detection for MULTI_CLASS_BOX and MULTI_CLASS_BOX_ACCURATE models true, false
mc_animal* Enable animals detection for MULTI_CLASS_BOX and MULTI_CLASS_BOX_ACCURATE models true, false
mc_electronics* Enable electronic devices detection for MULTI_CLASS_BOX and MULTI_CLASS_BOX_ACCURATE models true, false
mc_fruit_vegetable* Enable fruits and vegetables detection for MULTI_CLASS_BOX and MULTI_CLASS_BOX_ACCURATE models true, false
mc_sport* Enable sport related object detection for MULTI_CLASS_BOX and MULTI_CLASS_BOX_ACCURATE models true, false
body_fitting Enable/disable body fitting for HUMAN_BODY_FAST and HUMAN_BODY_ACCURATE models true,false
body_format Formato of the skeleton data 0: POSE_18 - 1: POSE_34 [Only if HUMAN_BODY_* model is selected]
qos_history How to queue messages 0: KEEP_LAST - 1: KEEP_ALL
qos_depth Size of the queue if KEEP_LAST int
qos_reliability Enable resending of not delivered message, if RELIABLE 0: BEST_EFFORT - 1: RELIABLE
qos_durability Enable storing of unread message if TRANSIENT_LOCAL 0: TRANSIENT_LOCAL - 1: VOLATILE

* Dynamic parameter

Mapping parameters

Namespace: mapping

common.yaml

Parameter Description Value
mapping_enabled Enable/disable the mapping module true, false
resolution Resolution of the fused point cloud [0.01, 0.2] double, default=0.1
max_mapping_range Maximum depth range while mapping in meters (-1 for automatic calculation) [2.0, 20.0] double
fused_pointcloud_freq Publishing frequency (Hz) of the 3D map as fused point cloud double
clicked_point_topic Topic published by Rviz when a point of the cloud is clicked. Used for plane detection string, default "/clicked_point"
qos_history How to queue messages 0: KEEP_LAST - 1: KEEP_ALL
qos_depth Size of the queue if KEEP_LAST int
qos_reliability Enable resending of not delivered message, if RELIABLE 0: BEST_EFFORT - 1: RELIABLE
qos_durability Enable storing of unread message if TRANSIENT_LOCAL 0: TRANSIENT_LOCAL - 1: VOLATILE

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.:

$ ros2 param set /zed/zed_node depth.confidence 80

if the parameter is set successfully, you will get a confirmation message:

Set parameter successful

In the case you tried to set a parameter that’s not dynamically reconfigurable, or you specified an invalid value, you will get this error:

$ ros2 param set /zed/zed_node depth.confidence 150
Set parameter failed

and the ZED node will report a warning message explaining the error type:

1538556595.265117561: [zed.zed_node] [WARN]	The param 'depth.confidence' requires an INTEGER value in the range ]0,100]

Transform frame

The ZED ROS2 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.

  • base_frame is the current position and orientation of the reference base of the robot.
  • <camera_name>_base_link is the current position and orientation of the ZED base center.
  • <camera_name>_camera_center is the current position and orientation of ZED, determined by visual odometry and the tracking module.
  • <camera_name>_right_camera is the position and orientation of the ZED’s right camera.
  • <camera_name>_right_camera_optical is the position and orientation of the ZED’s right camera optical frame.
  • <camera_name>_left_camera is the position and orientation of the ZED’s left camera.
  • <camera_name>_left_camera_optical is the position and orientation of the ZED’s left camera optical frame.
  • <camera_name>_imu_link is the origin of the inertial data frame (not available with ZED).
  • <camera_name>_mag_link is the origin of the magnetometer frame (ZED2/ZED2i only).
  • <camera_name>_baro_link is the origin of the barometer frame (ZED2/ZED2i only).
  • <camera_name>_temp_left_link is the origin of the left temperature frame (ZED2/ZED2i only).
  • <camera_name>_temp_right_link is the origin of the right temperature frame (ZED2/ZED2i only).

For RVIZ2 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 odometry” information. The map frame is updated using the Positional Tracking algorithm provided by the Stereolabs SDK, fusing the inertial information from the IMU sensor.

map_frame (`map`)
└─odometry_frame (`odom`)
   └─base_frame (`base_link`)
      └─camera_link (`<camera_name>_base_link`)
        └─camera_frame (`<camera_name>_camera_center`)
          └─left_camera_frame (`<camera_name>_left_camera_frame`)
          | └─left_camera_optical_frame (`<camera_name>_left_camera_optical_frame`)
          | └─imu_frame (`<camera_name>_imu_link`)
          └─right_camera_frame (`<camera_name>_right_camera_frame`) 
            └─right_camera_optical_frame (`<camera_name>_right_camera_optical_frame`)

Services

The ZED node provides the following services:

  • ~/enable_mapping: enable spatial mapping.
  • ~/enable_obj_det: enable object detection.
  • ~/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 service set_pose.
  • ~/reset_roi: Reset the Region of Interest to the full image frame.
  • ~/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]
  • ~/set_roi: Set the Region of Interest to the described polygon.
  • ~/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 if general.svo_realtime is false and if an SVO as been chosen as input source.

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:

$ ros2 service call /zed2/zed_node/enable_obj_det std_srvs/srv/SetBool data:\ true\

and the service server will reply:

waiting for service to become available...
requester: making request: std_srvs.srv.SetBool_Request(data=True)

response:
std_srvs.srv.SetBool_Response(success=True, message='Object Detection started')

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.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.