ZED ROS 2 Wrapper Custom Messages

Open in ClaudeOpen in ChatGPT

All the custom messages used by the ZED ROS 2 Wrapper are defined in the zed-ros2-interfaces repository and are installed along with the zed-msgs package:

$sudo apt install ros-<ros2-distro>-zed-msgs

Node Heartbeat

The zed_interfaces/Heartbeat message, published on the ~/status/heartbeat topic, is defined as:

$# Message to notify that the node is alive to other nodes
$
$# idx of the message
$uint64 beat_count
$
$# namespace of the node
$string node_ns
$# name of the node
$string node_name
$# full node name
$string full_name
$
$# serial number of the input camera
$uint32 camera_sn
$
$# data from an svo?
$bool svo_mode
$
$# data from simulation?
$bool simul_mode

Node Health Status

The zed_interfaces/HealthStatusStamped message, published on the ~/status/health topic, is defined as:

$# Message to provide information concerning the status of health of the ZED Camera
$
$# Standard Header
$std_msgs/Header header
$
$# ZED Camera serial number
$uint32 serial_number
$
$# ZED Camera name
$string camera_name
$
$# Image quality is degraded
$bool low_image_quality
$
$# Environmental light conditions are not optimal
$bool low_lighting
$
$# Depth reliability is low
$bool low_depth_reliability
$
$# Motion sensors reliability is low
$bool low_motion_sensors_reliability

SVO Status

The zed_interfaces/SVOStatus message, published on the ~/status/svo topic, is defined as:

$# Message to provide information concerning the status of the SVO playback
$
$# SVO File name
$string file_name
$
$# SVO playback status
$uint8 status
$
$# SVO playback status constants
$uint8 STATUS_PLAYING=0
$uint8 STATUS_PAUSED=1
$uint8 STATUS_END=2
$
$# SVO frame timestamp
$uint64 frame_ts
$
$# SVO playback position
$uint32 frame_id
$
$# SVO total number of frames
$uint32 total_frames
$
$# SVO loop status
$bool loop_active
$
$# SVO loop count
$uint32 loop_count
$
$# SVO real-time mode status
$bool real_time_mode

Plane Detection result

The zed_interfaces/PlaneStamped message, published by the Plane Detection module, is defined as:

$# Standard Header
$std_msgs/Header header
$
$# Mesh of the place
$shape_msgs/Mesh mesh
$
$# Representation of a plane, using the plane equation ax + by + cz + d = 0
$shape_msgs/Plane coefficients
$
$# Normal vector
$geometry_msgs/Point32 normal
$
$# Center point
$geometry_msgs/Point32 center
$
$# Plane pose relative to the global reference frame
$geometry_msgs/Transform pose
$
$# Width and height of the bounding rectangle around the plane contours
$float32[2] extents
$
$# The polygon bounds of the plane
$geometry_msgs/Polygon bounds

Depth information

The zed_interfaces/DepthInfoStamped message is defined as:

$# Standard Header
$std_msgs/Header header
$
$# Miminum measured depth
$float32 min_depth
$
$# Maximum measured depth
$float32 max_depth

Positional Tracking status

The zed_interfaces/PosTrackStatus message is defined as:

$# Status constants
$# SEARCHING - The camera is searching for a previously known position to locate itself
$# OK - Positional tracking is working normally
$# OFF - Positional tracking is not enabled.
$# FPS_TOO_LOW - Effective FPS is too low to give proper results for motion tracking. Consider using PERFORMANCES parameters (DEPTH_MODE_PERFORMANCE, low camera resolution (VGA,HD720))
$# SEARCHING_FLOOR_PLANE - The camera is searching for the floor plane to locate itself related to it, the REFERENCE_FRAME::WORLD will be set afterward.
$uint8 SEARCHING=0
$uint8 OK = 1
$uint8 OFF = 2
$uint8 FPS_TOO_LOW = 3
$uint8 SEARCHING_FLOOR_PLANE = 3
$
$# Status
$uint8 status

GNSS Fusion status

The zed_interfaces/GNSSFusionStatus message, published on the ~/pose/filtered/status topic, is defined as:

$# GNSS_FUSION_STATUS
$# Represents the current state of GNSS fusion for global localization.
$# OK - The GNSS fusion module is calibrated and working successfully.
$# OFF - The GNSS fusion module is not enabled.
$# CALIBRATION_IN_PROGRESS - Calibration of the GNSS/VIO fusion module is in progress.
$# RECALIBRATION_IN_PROGRESS- Re-alignment of GNSS/VIO data is in progress, leading to potentially inaccurate global position.
$uint8 OK = 0
$uint8 OFF = 1
$uint8 CALIBRATION_IN_PROGRESS = 2
$uint8 RECALIBRATION_IN_PROGRESS = 3
$
$uint8 gnss_fusion_status

Object Detection and Body Tracking results

The Object Detection and the Body Tracking modules publish data on the detected objects and body topics by using the same custom message.

The zed_interfaces/ObjectsStamped message is defined as:

$# Standard Header
$std_msgs/Header header
$
$# Array of `object_stamped` topics
$zed_interfaces/Object[] objects

where zed_interfaces/Object is defined as:

$# Object label
$string label
$
$# Object label ID
$int16 label_id
$
$# Object sub-class label (Only for the `MULTI_CLASS_BOX` model)
$string sublabel
$
$# Object confidence level (1-99)
$float32 confidence
$
$# Object 3D centroid position
$float32[3] position
$
$# Position covariance
$float32[6] position_covariance
$
$# Object 3D velocity
$float32[3] velocity
$
$# Is Object tracking available?
$bool tracking_available
$
$# Tracking available
$# Tracking state
$# 0 -> OFF (object not valid)
$# 1 -> OK
$# 2 -> SEARCHING (occlusion occurred, trajectory is estimated)
$# 3 -> TERMINATE (This is the last searching state of the track. The track will be deleted in the next frame).
$int8 tracking_state
$
$# Action state
$# 0 -> IDLE
$# 2 -> MOVING
$int8 action_state
$
$# 2D Bounding box projected to the Camera image
$zed_msgs/BoundingBox2Di bounding_box_2d
$
$# 3D Bounding box in world frame
$zed_msgs/BoundingBox3D bounding_box_3d
$
$# 3D dimensions (width, height, lenght)
$float32[3] dimensions_3d
$
$# =======================================
$# Person Head Detection specific fields
$# =======================================
$
$# 2D Bounding box projected to Camera image of the person head
$zed_msgs/BoundingBox2Df head_bounding_box_2d
$
$# 3D Bounding box in world frame of the person head
$zed_msgs/BoundingBox3D head_bounding_box_3d
$
$# 3D position of the centroid of the person head
$float32[3] head_position
$
$# ===============================
$# Body Tracking specific fields
$# ===============================
$# Is skeleton available?
$bool skeleton_available
$
$# Skeleton format
$# 0 -> POSE_18
$# 1 -> POSE_34
$# 2 -> POSE_38
$# 3 -> POSE_70
$int8 body_format
$
$# 2D Person skeleton projected to Camera image
$zed_msgs/Skeleton2D skeleton_2d
$
$# 3D Person skeleton in world frame
$zed_msgs/Skeleton3D skeleton_3d

And all the submessages are defined as following:

zed_interfaces/BoundingBox2Df:

$# 0 ------- 1
$# | |
$# | |
$# | |
$# 3 ------- 2
$zed_interfaces/Keypoint2Df[4] corners

zed_interfaces/BoundingBox2Di:

$# 0 ------- 1
$# | |
$# | |
$# | |
$# 3 ------- 2
$zed_interfaces/Keypoint2Di[4] corners

zed_interfaces/BoundingBox3D:

$# 1 ------- 2
$# /. /|
$# 0 ------- 3 |
$# | . | |
$# | 5.......| 6
$# |. |/
$# 4 ------- 7
$zed_interfaces/Keypoint3D[8] corners

zed_interfaces/Keypoint2Df:

$float32[2] kp

zed_interfaces/Keypoint2Di:

$uint32[2] kp

zed_interfaces/Keypoint3D:

$float32[3] kp

zed_interfaces/Skeleton2D:

$# Skeleton joints
$zed_interfaces/Keypoint2Df[70] keypoints

zed_interfaces/Skeleton3D:

$# Skeleton joints
$zed_interfaces/Keypoint3D[70] keypoints