Wiki

Overview

The ZED ROS wrapper provides access to all camera sensors and parameters through ROS topics, parameters and services. The zed-ros-wrapper is available for all ZED stereo cameras: ZED2, ZED Mini and ZED.

https://cdn.stereolabs.com/assets/images/zed-2/zed-2-front.jpg

Getting Started

Follow the official Stereolabs "Getting Started" guide to install the ZED ROS wrapper with all the latest features.

Github repositories

Start the node

The ZED Wrapper node with the default parameters can be started using one of the three launch files, according to the model of camera:

Published Topics

Left Camera

rgb/image_rect_color (sensor_msgs/Image)

rgb/image_rect_gray (sensor_msgs/Image) rgb/camera_info (sensor_msgs/CameraInfo) rgb_raw/image_raw_color (sensor_msgs/Image) rgb_raw/image_raw_gray (sensor_msgs/Image) rgb_raw/camera_info (sensor_msgs/CameraInfo) left/image_rect_color (sensor_msgs/CameraInfo) left/image_rect_gray (sensor_msgs/CameraInfo) left/camera_info (sensor_msgs/CameraInfo) left_raw/image_raw_color (sensor_msgs/CameraInfo) left_raw/image_raw_gray (sensor_msgs/CameraInfo) left_raw/camera_info (sensor_msgs/CameraInfo)

Right Camera

right/image_rect_color (sensor_msgs/Image)

right/image_rect_gray (sensor_msgs/Image) right/camera_info (sensor_msgs/CameraInfo) right_raw/image_raw_color (sensor_msgs/Image) right_raw/image_raw_gray (sensor_msgs/Image) right_raw/camera_info (sensor_msgs/)

Sensors

imu/data (sensor_msgs/Imu)

imu/data_raw (sensor_msgs/Imu) imu/mag (sensor_msgs/MagneticField) atm_press (sensor_msgs/FluidPressure) temperature/imu (sensor_msgs/Temperature) temperature/left (sensor_msgs/Temperature) temperature/right (sensor_msgs/Temperature) left_cam_imu_transform (geometry_msgs/Transform)

Stereo Pair

stereo/image_rect_color (sensor_msgs/Image)

stereo_raw/image_raw_color (sensor_msgs/Image)

to retrieve the camera parameters you can subscribe to the topics left/camera_info, right/camera_info, left_raw/camera_info and right_raw/camera_info

Depth and Point Cloud

depth/depth_registered (sensor_msgs/Image)

depth/camera_info (sensor_msgs/CameraInfo) point_cloud/cloud_registered (sensor_msgs/PointCloud2) confidence/confidence_map (sensor_msgs/Image) disparity/disparity_image (stereo_msgs/DisparityImage)

Positional Tracking

odom (nav_msgs/Odometry)

pose (geometry_msgs/PoseStamped) pose_with_covariance (geometry_msgs/PoseWithCovarianceStamped) path_odom (nav_msgs/Path) path_map (nav_msgs/Path)

Mapping

mapping/fused_cloud (sensor_msgs/PointCloud2)

  • Published only if mapping is enabled, see mapping/mapping_enabled parameter and start_3d_mapping service.

Object Detection [only ZED 2]

objects (zed_interfaces/object_stamped)

object_markers (visualization_msgs/MarkerArray)

  • Published only if Object Detection is enabled, see object_detection/od_enabled parameter and start_object_detection service.

Diagnostic

diagnostics (diagnostic_msgs/DiagnosticStatus)

Node Parameters

You can specify the parameters to be used by the ZED node modifying the values in the files

General Parameters

general/camera_name (string, default: "zed")

general/camera_model (string, default: "zed") general/zed_id (int, default: 0) general/serial_number (int, default: 0) general/resolution (int, default: 2) general/grab_frame_rate (int, default: 30) general/gpu_id (int, default: -1) general/base_frame (string, default: "base_link") general/verbose (bool, default: false) general/svo_compression (int, default: 2) general/self_calib (bool, default: true) general/camera_flip (bool, default: false)

Video Parameters

video/img_downsample_factor (double, default: 1.0)

video/extrinsic_in_camera_frame (bool, default: true)

Sensor Parameters [only ZED-M and ZED 2]

sensors/sensors_timestamp_sync (bool, default: false)

Depth Parameters

depth/quality (int, default: 1)

depth/sensing_mode (int, default: 0) depth/depth_stabilization (bool, default: true) depth/openni_depth_mode (int, default: 0) depth/min_depth (float, default: 0.7) depth/max_depth (float, default: 10.0) depth/depth_downsample_factor (double, default: 1.0)

Position Parameters

pos_tracking/publish_tf (bool, default: true)

pos_tracking/publish_map_tf (bool, default: true) pos_tracking/map_frame (string, default: "map") pos_tracking/odometry_frame (string, default: "odom") pos_tracking/area_memory (bool, default: true) pos_tracking/pose_smoothing (bool, default: true) pos_tracking/area_memory_db_path (string, default: "") pos_tracking/floor_alignment (bool, default: false) pos_tracking/initial_base_pose (array, default: [0.0,0.0,0.0, 0.0,0.0,0.0]) pos_tracking/init_odom_with_first_valid_pose (bool, default: true) pos_tracking/path_pub_rate (float, default: 2.0) pos_tracking/path_max_count (int, default: -1)

Mapping Parameters

mapping/mapping_enabled (bool, default: false)

mapping/resolution (float, default: 0.1) mapping/max_mapping_range (float, default: -1.0) mapping/fused_pointcloud_freq (float, default: 1.0)

Object Detection Parameters [only ZED 2]

object_detection/od_enabled (bool, default: false)

object_detection/confidence_threshold (int, default: 50) object_detection/object_tracking_enabled (bool, default: true) object_detection/people_detection (bool, default: true) object_detection/vehicle_detection (bool, default: true)

Dynamic Parameters

Dynamic parameters cannot have a namespace, so they cannot be placed within their correct module. A note is added in the description of the parameter to reflect the correct module they belong.

pub_frame_rate (float, default: 15.0)

depth_confidence (int, default: 100) depth_texture_conf (int, default: 100) point_cloud_freq (float, default: 15.0) brightness (int, default: 4) contrast (int, default: 4) hue (int, default: 0) saturation (int, default: 4) sharpness (int, default: 3) gamma (int, default: 8) auto_exposure_gain (bool, default: true) gain (int, default: 100) exposure (int, default: 100) auto_whitebalance (bool, default: true) whitebalance_temperature (int, default: 42)

Services

start_svo_recording (zed_interfaces/start_svo_recording)

stop_svo_recording (zed_interfaces/stop_svo_recording) start_remote_stream (zed_interfaces/start_remote_stream) stop_remote_stream (zed_interfaces/stop_remote_stream) set_pose (zed_interfaces/set_pose) reset_tracking (zed_interfaces/reset_tracking) reset_odometry (zed_interfaces/reset_odometry) set_led_status (zed_interfaces/set_led_status) toggle_led (zed_interfaces/toggle_led) start_3d_mapping (zed_interfaces/start_3d_mapping) stop_3d_mapping (zed_interfaces/stop_3d_mapping) start_object_detection (zed_interfaces/start_object_detection) stop_3d_mapping (zed_interfaces/stop_3d_mapping)

Nodelets

The zed_wrapper package contains the standalone ZED Wrapper node that can be started as is using the provided launch files, as described in the ZED Wrapper Node documentation.

But the ZED Wrapper has been designed to take the maximum advantage of the nodelet package, in order to run multiple algorithms in the same process with zero copy transport between algorithms.

The core of the ZED Wrapper is indeed the ZEDWrapperNodelet nodelet, available in the zed_nodelets package that provides the interface between the ZED SDK and the ROS environment.

zed_nodelets/ZEDWrapperNodelet

Same usage as the zed_wrapper_node.

Available as: zed_nodelets/ZEDWrapperNodelet

zed_nodelets/RgbdSensorsSyncNodelet

Sometimes it is useful to synchronize and mux a few topics in one single topic using their timestamp, for example to save a rosbag or to guarantee that all the topics published in the same instant are received on the other side of a network. To perform this operation we provide the nodelet zed_nodelets/RgbdSensorsSyncNodelet that allows to synchronize RGB, Depth, IMU and Magnetometer information in a single custom topic RGBDSensors.

Subscribed Topics

rgb/image_rect_color (sensor_msgs/Image) depth/depth_registered (sensor_msgs/Image) rgb/camera_info (sensor_msgs/CameraInfo) imu/data (sensor_msgs/Imu) imu/mag (sensor_msgs/MagneticField)

Published Topics

rgbd_sync (zed_interfaces/RGBDSensors)

Parameters

~zed_nodelet_name (string, default: zed_nodelet) ~approx_sync (bool, default: true) ~queue_size (int, default: 600) ~sub_imu (bool, default: true) ~sub_mag (bool, default: true)

zed_nodelets/RgbdSensorsDemuxNodelet

A RGBDSensors topic message cannot be used by the standard ROS node. You must create your own node that subscribes it and extract all the available data. To make it easier to access the information stored in the RGBDSensors topic, we provide a demux nodelet: RgbdSensorsDemuxNodelet.

Subscribed Topics

rgbd_sync (zed_interfaces/RGBDSensors)

Published Topics

rgb/image_rect_color (sensor_msgs/Image) depth/depth_registered (sensor_msgs/Image) rgb/camera_info (sensor_msgs/CameraInfo) imu/data (sensor_msgs/Imu) imu/mag (sensor_msgs/MagneticField)

Examples and Tutorials

With the release v3.0 of the ZED Wrapper the examples and the tutorials have been removed from the main repository and a new special repository has been created.

Examples

Tutorials

Output visualization

Report an Issue

If you encounter an issue with the zed-ros-wrapper, please refer to the dedicated issue list on Github.

Wiki: zed-ros-wrapper (last edited 2020-03-20 18:44:33 by Walter Lucetti)