<> <> == 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: [[https://www.stereolabs.com/zed-2/|ZED2]], [[https://www.stereolabs.com/zed-mini/|ZED Mini]] and [[https://www.stereolabs.com/zed/|ZED]]. {{https://cdn.stereolabs.com/assets/images/zed-2/zed-2-front.jpg||width="70%"}} == Getting Started == Follow the official [[https://www.stereolabs.com/docs/ros/|Stereolabs "Getting Started"]] guide to install the ZED ROS wrapper with all the latest features. === Github repositories === * [[https://github.com/stereolabs/zed-ros-wrapper|zed-ros-wrapper]]: this is the main repository. It contains the source code of the ZED Wrapper node and the instruction about how to compile and run it. * [[https://github.com/stereolabs/zed-ros-examples|zed-ros-examples]]: this repository is a collection of examples and tutorials to illustrate how to better use the ZED cameras in the ROS framework. == 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: * '''ZED:''' `$ roslaunch zed_wrapped zed.launch` * '''ZED Mini:''' `$ roslaunch zed_wrapped zedm.launch` * '''ZED 2:''' `$ roslaunch zed_wrapped zed2.launch` == Published Topics == === Left Camera === {{{ #!clearsilver CS/NodeAPI pub { no_header = True 0{ name = rgb/image_rect_color type = sensor_msgs/Image desc = Color rectified image (left RGB image by default). } 1{ name = rgb/image_rect_gray type = sensor_msgs/Image desc = Grayscale rectified image (left RGB image by default). } 2{ name = rgb/camera_info type = sensor_msgs/CameraInfo desc = Color camera calibration data. } 3{ name = rgb_raw/image_raw_color type = sensor_msgs/Image desc = Color unrectified image (left RGB image by default). } 4{ name = rgb_raw/image_raw_gray type = sensor_msgs/Image desc = Grayscale unrectified image (left RGB image by default). } 5{ name = rgb_raw/camera_info type = sensor_msgs/CameraInfo desc = Color unrectified camera calibration data. } 6{ name = left/image_rect_color type = sensor_msgs/CameraInfo desc = Left camera color rectified image. } 7{ name = left/image_rect_gray type = sensor_msgs/CameraInfo desc = Left camera grayscale rectified image. } 8{ name = left/camera_info type = sensor_msgs/CameraInfo desc = Left camera calibration data. } 9{ name = left_raw/image_raw_color type = sensor_msgs/CameraInfo desc = Left camera color unrectified image. } 10{ name = left_raw/image_raw_gray type = sensor_msgs/CameraInfo desc = Left camera grayscale unrectified image. } 11{ name = left_raw/camera_info type = sensor_msgs/CameraInfo desc = Left unrectified camera calibration data. } } }}} === Right Camera === {{{ #!clearsilver CS/NodeAPI pub { no_header = True 0{ name = right/image_rect_color type = sensor_msgs/Image desc = Color rectified right image. } 1{ name = right/image_rect_gray type = sensor_msgs/Image desc = Grayscale rectified right image. } 2{ name = right/camera_info type = sensor_msgs/CameraInfo desc = Right camera calibration data. } 3{ name = right_raw/image_raw_color type = sensor_msgs/Image desc = Color unrectified right image. } 4{ name = right_raw/image_raw_gray type = sensor_msgs/Image desc = Grayscale unrectified right image. } 5{ name = right_raw/camera_info type = sensor_msgs/ desc = Right unrectified camera calibration data. } } }}} === Sensors === {{{ #!clearsilver CS/NodeAPI pub { no_header = True 0{ name = imu/data type = sensor_msgs/Imu desc = Accelerometer, gyroscope, and orientation data in Earth frame [only ZED-M and ZED 2]. } 1{ name = imu/data_raw type = sensor_msgs/Imu desc = Accelerometer and gyroscope data in Earth frame [only ZED-M and ZED 2]. } 2{ name = imu/mag type = sensor_msgs/MagneticField desc = Calibrated magnetometer data [only ZED 2]. } 3{ name = atm_press type = sensor_msgs/FluidPressure desc = Atmospheric pressure data [only ZED 2]. } 4{ name = temperature/imu type = sensor_msgs/Temperature desc = Temperature of the IMU sensor [only ZED 2]. } 5{ name = temperature/left type = sensor_msgs/Temperature desc = Temperature of the left camera sensor [only ZED 2]. } 6{ name = temperature/right type = sensor_msgs/Temperature desc = Temperature of the right camera sensor [only ZED 2]. } 7{ name = left_cam_imu_transform type = geometry_msgs/Transform desc = Transform from left camera to IMU sensor position. } } }}} === Stereo Pair === {{{ #!clearsilver CS/NodeAPI pub { no_header = True 0{ name = stereo/image_rect_color type = sensor_msgs/Image desc = Stereo rectified pair images side-by-side. } 1{ name = stereo_raw/image_raw_color type = sensor_msgs/Image desc = stereo unrectified pair images side-by-side. } } }}} {{{#!wiki tip 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 === {{{ #!clearsilver CS/NodeAPI pub { no_header = True 0{ name = depth/depth_registered type = sensor_msgs/Image desc = Depth map image registered on left image (32-bit float in meters by default). } 1{ name = depth/camera_info type = sensor_msgs/CameraInfo desc = Depth camera calibration data. } 2{ name = point_cloud/cloud_registered type = sensor_msgs/PointCloud2 desc = Registered color point cloud. } 3{ name = confidence/confidence_map type = sensor_msgs/Image desc = Confidence map (floating point values to be used in your own algorithms). } 4{ name = disparity/disparity_image type = stereo_msgs/DisparityImage desc = Disparity map. } } }}} === Positional Tracking === {{{ #!clearsilver CS/NodeAPI pub { no_header = True 0{ name = odom type = nav_msgs/Odometry desc = Camera position and orientation in free space relative the Odometry frame (pure visual odometry for ZED, visual-intertial for ZED 2 and ZED-M). } 1{ name = pose type = geometry_msgs/PoseStamped desc = Camera position and orientation in free space relative the Map frame (given by sensor fusion + SLAM + loop closure algorithm). } 2{ name = pose_with_covariance type = geometry_msgs/PoseWithCovarianceStamped desc = Camera pose relative to Map frame with covariance. } 3{ name = path_odom type = nav_msgs/Path desc = Trajectory of the camera in Map frame without loop closures (continuous). } 4{ name = path_map type = nav_msgs/Path desc = Trajectory of the camera in Map frame with loop closures (may contain jumps). } } }}} === Mapping === {{{ #!clearsilver CS/NodeAPI pub { no_header = True 0{ name = mapping/fused_cloud type = sensor_msgs/PointCloud2 desc = 3D point cloud map generated from fusion of point cloud over the camera trajectory. } } }}} {{{#!wiki tip Published only if mapping is enabled, see `mapping/mapping_enabled` parameter and `start_3d_mapping` service. }}} === Object Detection [only ZED 2] === {{{ #!clearsilver CS/NodeAPI pub { no_header = True 0{ name = objects type = zed_interfaces/object_stamped desc = Array of the detected/tracked objects for each camera frame [only ZED 2]. } 1{ name = object_markers type = visualization_msgs/MarkerArray desc = Array of markers of the detected/tracked objects to be rendered in Rviz [only ZED 2]. } } }}} {{{#!wiki tip Published only if Object Detection is enabled, see `object_detection/od_enabled` parameter and `start_object_detection` service. }}} === Diagnostic === {{{ #!clearsilver CS/NodeAPI pub { no_header = True 0{ name = diagnostics type = diagnostic_msgs/DiagnosticStatus desc = ROS diagnostic message for ZED cameras. } }}} == Node Parameters == You can specify the parameters to be used by the ZED node modifying the values in the files * `params/common.yaml`: common parameters to all camera models * `params/zed.yaml`: parameters for the ZED camera * `params/zedm.yaml`: parameters for the ZED Mini camera * `params/zed2.yaml`: parameters for the ZED 2 camera === General Parameters === {{{ #!clearsilver CS/NodeAPI param { no_header = True 0{ name = general/camera_name type = string desc = A custom name for the ZED camera. Used as namespace and prefix for camera TF frames default = "zed" } 1{ name = general/camera_model type = string desc = Type of Stereolabs camera. Used to load the correct model in RVIZ example and to start the correct SDK modules. default = "zed" } 2{ name = general/zed_id type = int desc = 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 default = 0 } 3{ name = general/serial_number type = int desc = Select a ZED camera by its Serial Number default = 0 } 4{ name = general/resolution type = int desc = Set ZED camera resolution [0: HD2K, 1: HD1080, 2: HD720, 3: VGA] default = 2 } 5{ name = general/grab_frame_rate type = int desc = Set ZED camera video framerate default = 30 } 6{ name = general/gpu_id type = int desc = Select a GPU device for depth computation default = -1 } 7{ name = general/base_frame type = string desc = Frame_id of the frame that indicates the reference base of the robot default = "base_link" } 8{ name = general/verbose type = bool desc = Enable/disable the verbosity of the SDK default = false } 9{ name = general/svo_compression type = int desc = Set SVO compression mode for saving [0: LOSSLESS (PNG/ZSTD), 1: H264 (AVCHD) ,2: H265 (HEVC)] default = 2 } 10{ name = general/self_calib type = bool desc = Enable/disable self calibration at starting default = true } 11{ name = general/camera_flip type = bool desc = Flip the camera data if it is mounted upsidedown default = false } }}} === Video Parameters === {{{ #!clearsilver CS/NodeAPI param { no_header = True 0{ name = video/img_downsample_factor type = double desc = Resample factor for images [0.01,1.0]. The SDK works with native image sizes, but publishes rescaled image. default = 1.0 } 1{ name = video/extrinsic_in_camera_frame type = bool desc = 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] default = true } }}} === Sensor Parameters [only ZED-M and ZED 2] === {{{ #!clearsilver CS/NodeAPI param { no_header = True 0{ name = sensors/sensors_timestamp_sync type = bool desc = Synchronize Sensors message timestamp with latest received frame default = false } }}} === Depth Parameters === {{{ #!clearsilver CS/NodeAPI param { no_header = True 0{ name = depth/quality type = int desc = Select depth map quality [0: NONE, 1: PERFORMANCE, 2: MEDIUM, 3: QUALITY, 4: ULTRA] default = 1 } 1{ name = depth/sensing_mode type = int desc = Select depth sensing mode (change only for VR/AR applications) [0: STANDARD, 1: FILL] default = 0 } 2{ name = depth/depth_stabilization type = bool desc = Enable depth stabilization. Stabilizing the depth requires an additional computation load as it enables tracking default = true } 3{ name = depth/openni_depth_mode type = int desc = Convert 32bit depth in meters to 16bit in millimeters [0: 32bit float meters, 1: 16bit uchar millimeters] default = 0 } 4{ name = depth/min_depth type = float desc = Minimum value allowed for depth measures. Min: 0.3 (ZED), 0.1 (ZED-M) 0.2 (ZED 2), Max: 3.0 - '''Note:''' reducing this value will require more computational power and RAM memory. In cases of limited computation power, increasing this value can provide better performance. default = 0.7 } 5{ name = depth/max_depth type = float desc = Maximum value allowed for depth measures [Min: 1.0, Max: 30.0 - Values beyond this limit will be reported as TOO_FAR] default = 10.0 } 6{ name = depth/depth_downsample_factor type = double desc = Resample factor for depth data matrices [0.01,1.0]. The SDK works with native data sizes, but publishes rescaled matrices (depth map, point cloud, ...) default = 1.0 } }}} === Position Parameters === {{{ #!clearsilver CS/NodeAPI param { no_header = True 0{ name = pos_tracking/publish_tf type = bool desc = Enable/disable publishing of the transforms between `odom → base_link` and `imu_link → base_link`. '''Note:''' The IMU frame can be published at a higher frequency than odom and map. default = true } 1{ name = pos_tracking/publish_map_tf type = bool desc = Enable/disable publishing of the map TF frame relative to the position of the base frame (i.e. `base_link`) in the map frame. '''Note:''' the value is ignored if `publish_tf` is false. default = true } 3{ name = pos_tracking/map_frame type = string desc = Frame_id of the pose message default = "map" } 4{ name = pos_tracking/odometry_frame type = string desc = Frame_id of the odom message default = "odom" } 5{ name = pos_tracking/area_memory type = bool desc = Enable area learning to correct odometry drift with loop closures. default = true } 6{ name = pos_tracking/pose_smoothing type = bool desc = Enable smoothing of pose correction when drift is detected with loop closures. Only available if area_memory is enabled. default = true } 7{ name = pos_tracking/area_memory_db_path type = string desc = Path of the database file for loop closure and relocalization that contains learnt visual information about the environment. default = "" } 8{ name = pos_tracking/floor_alignment type = bool desc = If true, it detects the floor plane during position tracking initialization. The initial pose of `zed_camera_center` in map frame is estimated relative to the floor plane and the initial pose of `base_link` is recomputed according to the TF tree. default = false } 9{ name = pos_tracking/initial_base_pose type = array desc = Set the the initial pose of `base_link`in `map` frame -> [X, Y, Z, R, P, Y] default = [0.0,0.0,0.0, 0.0,0.0,0.0] } 11{ name = pos_tracking/init_odom_with_first_valid_pose type = bool desc = Set the initial pose of the odometry with the first valid pose received from positional tracking. Format: "x y z roll pitch yaw". default = true } 12{ name = pos_tracking/path_pub_rate type = float desc = Frequency (Hz) of publishing of the path messages default = 2.0 } 13{ name = pos_tracking/path_max_count type = int desc = Maximum number of poses kept in the pose arrays (-1 for infinite) default = -1 } }}} === Mapping Parameters === {{{ #!clearsilver CS/NodeAPI param { no_header = True 0{ name = mapping/mapping_enabled type = bool desc = Enable/disable the mapping module default = false } 1{ name = mapping/resolution type = float desc = Resolution of the fused point cloud [0.01, 0.2] default = 0.1 } 2{ name = mapping/max_mapping_range type = float desc = Maximum depth range used for mapping, in meters (-1 to use recommended range depending on the selected resolution) [2.0, 20.0] default = -1.0 } 3{ name = mapping/fused_pointcloud_freq type = float desc = Publishing frequency (Hz) of the 3D map as fused point cloud default = 1.0 } }}} === Object Detection Parameters [only ZED 2] === {{{ #!clearsilver CS/NodeAPI param { no_header = True 0{ name = object_detection/od_enabled type = bool desc = Enable/disable the Object Detection module default = false } 1{ name = object_detection/confidence_threshold type = int desc = Minimum value of the detection confidence of an object [0,100] default = 50 } 2{ name = object_detection/object_tracking_enabled type = bool desc = Enable/disable the tracking of the detected objects default = true } 3{ name = object_detection/people_detection type = bool desc = Enable/disable the detection of persons default = true } 4{ name = object_detection/vehicle_detection type = bool desc = Enable/disable the detection of vehicles default = true } }}} === Dynamic Parameters === {{{#!wiki tip 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. }}} {{{ #!clearsilver CS/NodeAPI param { no_header = True 0{ name = pub_frame_rate type = float desc = '''[General]''' Frequency of the publishing of Video and Depth images (equal or minor to grab_frame_rate value) [0.1,60.0] default = 15.0 } 1{ name = depth_confidence type = int desc = '''[Depth]''' Threshold to reject depth values based on their confidence. Each depth pixel has a corresponding confidence. A lower value means more confidence and precision (but less density). An upper value reduces filtering (more density, less certainty). A value of 100 will allow values from 0 to 100. (no filtering). A value of 90 will allow values from 10 to 100. (filtering lowest confidence values). A value of 30 will allow values from 70 to 100. (keeping highest confidence values and lowering the density of the depth map). The value should be in [1,100]. By default, the confidence threshold is set at 100, meaning that no depth pixel will be rejected. default = 100 } 2{ name = depth_texture_conf type = int desc = '''[Depth]''' Threshold to reject depth values based on their textureness confidence. A lower value means more confidence and precision (but less density). An upper value reduces filtering (more density, less certainty). The value should be in [1,100]. By default, the confidence threshold is set at 100, meaning that no depth pixel will be rejected. default = 100 } 3{ name = point_cloud_freq type = float desc = '''[Depth]''' Frequency of the pointcloud publishing (equal or minor to grab_frame_rate value) [0.1,60.0] default = 15.0 } 4{ name = brightness type = int desc = '''[Camera]''' Defines the brightness control [0,8] default = 4 } 5{ name = contrast type = int desc = '''[Camera]''' Defines the contrast control [0,8] default = 4 } 6{ name = hue type = int desc = '''[Camera]''' Defines the hue control [0,11] default = 0 } 7{ name = saturation type = int desc = '''[Camera]''' Defines the saturation control [0,8] default = 4 } 8{ name = sharpness type = int desc = '''[Camera]''' Defines the sharpness control [0,8] default = 3 } 9{ name = gamma type = int desc = '''[Camera]''' Defines the sharpness control [1,9] '''Note:''' available with ZED SDK >=v3.1 default = 8 } 10{ name = auto_exposure_gain type = bool desc = '''[Camera]''' Defines if the Gain and Exposure are in automatic mode or not default = true } 11{ name = gain type = int desc = '''[Camera]''' Defines the gain control [only if auto_exposure_gain is false] [0,100] default = 100 } 12{ name = exposure type = int desc = '''[Camera]''' Defines the exposure control [only if auto_exposure_gain is false] [0,100] default = 100 } 13{ name = auto_whitebalance type = bool desc = '''[Camera]''' Defines if the White balance is in automatic mode or not default = true } 14{ name = whitebalance_temperature type = int desc = '''[Camera]''' Defines the color temperature value (x100) [42,65] default = 42 } }}} == Services == {{{ #!clearsilver CS/NodeAPI srv { no_header = True 0{ name = start_svo_recording type = zed_interfaces/start_svo_recording desc = Starts 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/ } 1{ name = stop_svo_recording type = zed_interfaces/stop_svo_recording desc = Stops an active SVO recording } 2{ name = start_remote_stream type = zed_interfaces/start_remote_stream desc = Starts streaming over network to allow processing of ZED data on a remote machine. See [[https://www.stereolabs.com/docs/ros/zed_node/#remote-streaming|Remote streaming]] } 3{ name = stop_remote_stream type = zed_interfaces/stop_remote_stream desc = Stops streaming over network } 4{ name = set_pose type = zed_interfaces/set_pose desc = Sets the current camera pose in map frame to the value passed as parameter. For example, can be used with GPS position corrections. } 5{ name = reset_tracking type = zed_interfaces/reset_tracking desc = Resets position in /map frame to the initial pose value available in the param server. } 6{ name = reset_odometry type = zed_interfaces/reset_odometry desc = Resets the odometry to the last pose in map frame received from positional tracking. It can be used to reset to the current "map position" when the odometry drift is large. } 7{ name = set_led_status type = zed_interfaces/set_led_status desc = Sets the status of the blue led -> True: LED ON, False: LED OFF } 8{ name = toggle_led type = zed_interfaces/toggle_led desc = Toggles the status of the blue led, returning the new status } 9{ name = start_3d_mapping type = zed_interfaces/start_3d_mapping desc = Starts the Spatial Mapping processing. See [[https://www.stereolabs.com/docs/ros/zed_node/#spatial-mapping|Spatial Mapping]] } 10{ name = stop_3d_mapping type = zed_interfaces/stop_3d_mapping desc = Stops the Spatial Mapping processing (works also with automatic start from configuration file) } 11{ name = start_object_detection type = zed_interfaces/start_object_detection desc = Starts the Object Detection processing. See [[https://www.stereolabs.com/docs/ros/zed_node/#object-detection|Object Detection]] '''Note''': returns error if not using a ZED 2 camera } 12{ name = stop_3d_mapping type = zed_interfaces/stop_3d_mapping desc = Stops the Object Detection processing (works also with automatic start from configuration file) } } }}} == 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 [[https://www.stereolabs.com/docs/ros/zed_node/|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 [[https://github.com/stereolabs/zed-ros-wrapper/tree/master/zed_nodelets|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 {{{ #!clearsilver CS/NodeAPI node { name = zed_nodelets/RgbdSensorsSyncNodelet desc = 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. sub { 0.name = rgb/image_rect_color 0.type = sensor_msgs/Image 0.desc = RGB image stream. 1.name = depth/depth_registered 1.type = sensor_msgs/Image 1.desc = Registered depth image stream. 2.name = rgb/camera_info 2.type = sensor_msgs/CameraInfo 2.desc = RGB camera metadata. 3.name = imu/data 3.type = sensor_msgs/Imu 3.desc = Inertial data 4.name = imu/mag 4.type = sensor_msgs/MagneticField 4.desc = Magnetometer data } pub { 0.name = rgbd_sync 0.type = zed_interfaces/RGBDSensors 0.desc = The sync topic with RGB, Depth, Imu and Magnetometer data } param { 0.name = ~zed_nodelet_name 0.type = string 0.desc = The name of the ZED nodelet publishing the topics to be synchronized. 0.default = zed_nodelet 1.name = ~approx_sync 1.type = bool 1.desc = Use approximate synchronization for the input topics. If false all the message must have the same timestamp, this is almost impossible if subscribing also to IMU and Magnetometer topics and the parameter sensors_timestamp_sync is false in the ZED nodelet. 1.default = true 2.name = ~queue_size 2.type = int 2.desc = Size of message queue for each synchronized topic. 2.default = 600 3.name = ~sub_imu 3.type = bool 3.desc = Synchronize IMU messages. 3.default = true 4.name = ~sub_mag 4.type = bool 4.desc = Synchronize Magnetometer messages. 4.default = true } } }}} {{{ #!clearsilver CS/NodeAPI node { name = zed_nodelets/RgbdSensorsDemuxNodelet desc = 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. sub { 0.name = rgbd_sync 0.type = zed_interfaces/RGBDSensors 0.desc = The sync topic with RGB, Depth, Imu and Magnetometer data to be demuxed } pub { 0.name = rgb/image_rect_color 0.type = sensor_msgs/Image 0.desc = RGB image stream. 1.name = depth/depth_registered 1.type = sensor_msgs/Image 1.desc = Registered depth image stream. 2.name = rgb/camera_info 2.type = sensor_msgs/CameraInfo 2.desc = RGB camera metadata. 3.name = imu/data 3.type = sensor_msgs/Imu 3.desc = Inertial data (only if published by `zed_nodelets/RgbdSensorsSyncNodelet`) 4.name = imu/mag 4.type = sensor_msgs/MagneticField 4.desc = Magnetometer data (only if published by `zed_nodelets/RgbdSensorsSyncNodelet`) } } }}} == 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 [[https://github.com/stereolabs/zed-ros-examples|special repository]] has been created. === Examples === * [[https://github.com/stereolabs/zed-ros-examples/tree/master/examples/zed_nodelet_example|zed_nodelet_example]]: shows how to use the nodelet intraprocess communication. * [[https://github.com/stereolabs/zed-ros-examples/tree/master/examples/zed_rtabmap_example|zed_rtabmap_example]]: shows how to use the ZED with the RTABMap package to generate a 3D map with the rtabmap_ros package. * [[https://github.com/stereolabs/zed-ros-examples/tree/master/examples/zed_ar_track_alvar_example|zed_ar_track_alvar_example]]: shows how to use the ZED with the ar_track_alvar package to detect and track the position of AR tags. === Tutorials === * [[https://github.com/stereolabs/zed-ros-examples/tree/master/tutorials/zed_video_sub_tutorial|zed_video_sub_tutorial]]: in this tutorial you will learn how to write a simple node that subscribes to messages of type sensor_msgs/Image to retrieve the Left and Right rectified images published by the ZED node. * [[https://github.com/stereolabs/zed-ros-examples/tree/master/tutorials/zed_depth_sub_tutorial|zed_depth_sub_tutorial]]: in this tutorial you will learn how to write a simple node that subscribes to messages of type sensor_msgs/Image to retrieve the depth images published by the ZED node and to get the measured distance at the center of the image. * [[https://github.com/stereolabs/zed-ros-examples/tree/master/tutorials/zed_tracking_sub_tutorial|zed_tracking_sub_tutorial]]: in this tutorial you will learn how to write a simple node that subscribes to messages of type geometry_msgs/PoseStamped and nav_msgs/Odometry to retrieve the position and the orientation of the ZED camera in the map and in the odometry frames. * [[https://github.com/stereolabs/zed-ros-examples/tree/master/tutorials/zed_obj_det_sub_tutorial|zed_obj_det_sub_tutorial]]: in this tutorial you will learn how to write a simple node that subscribes to messages of type zed_interfaces/objects to retrieve the list of objects detected by a ZED 2 camera Object Detection module. * [[https://github.com/stereolabs/zed-ros-examples/tree/master/tutorials/zed_sensors_sub_tutorial|zed_sensors_sub_tutorial]]: in this tutorial you will learn how to write a simple node that subscribes to messages of type sensor_msgs/Imu, sensor_msgs/MagneticField, sensor_msgs/Temperature and sensor_msgs/FluidPressure published by ZED Mini and ZED 2. === Output visualization === * [[https://github.com/stereolabs/zed-ros-examples/tree/master/zed_display_rviz|zed_display_rviz]]: launch files to start many preconfigured [[rviz]] instances to display all the information provided by [[https://www.stereolabs.com/zed-2/|ZED2]], [[https://www.stereolabs.com/zed-mini/|ZED Mini]] and [[https://www.stereolabs.com/zed/|ZED]]. * [[https://github.com/stereolabs/zed-ros-examples/tree/master/tutorials/zed_sensors_sub_tutorial|zed_sensors_sub_tutorial]]: launch files to display sensor data with [[http://wiki.ros.org/plotjuggler|plotjuggler]] ([[https://www.stereolabs.com/docs/ros/sensors-data/#sensor-data-visualization-with-plotjuggler|more info]]) == Report an Issue == If you encounter an issue with the zed-ros-wrapper, please refer to the dedicated issue list on [[https://github.com/stereolabs/zed-ros-wrapper/issues|Github]]. ## AUTOGENERATED DON'T DELETE ## CategoryStack