ZED ROS 2 Wrapper Custom Messages

All the custom messages used by the ZED ROS 2 Wrapper are defined in the zed-ros2-interfaces repository.

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

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
string sublabel

# Object confidence level (1-99)
float32 confidence

# Object centroid position
float32[3] position

# Position covariance
float32[6] position_covariance

# Object velocity
float32[3] velocity

bool tracking_available

# Tracking available
# Tracking state
# 0 -> OFF (object not valid)
# 1 -> OK
# 2 -> SEARCHING (occlusion occurred, trajectory is estimated)
int8 tracking_state

# Action state
# 0 -> IDLE
# 2 -> MOVING
int8 action_state

# 2D Bounding box projected to Camera image
zed_interfaces/BoundingBox2Di bounding_box_2d

# 3D Bounding box in world frame
zed_interfaces/BoundingBox3D bounding_box_3d

# 3D dimensions (width, height, lenght)
float32[3] dimensions_3d

# Is skeleton available?
bool skeleton_available

# Skeleton format
# 0 -> POSE_18
# 1 -> POSE_34
# 2 -> POSE_38
# 3 -> POSE_70
int8 body_format

# 2D Bounding box projected to Camera image of the person head
zed_interfaces/BoundingBox2Df head_bounding_box_2d

# 3D Bounding box in world frame of the person head
zed_interfaces/BoundingBox3D head_bounding_box_3d

# 3D position of the centroid of the person head
float32[3] head_position

# 2D Person skeleton projected to Camera image
zed_interfaces/Skeleton2D skeleton_2d

# 3D Person skeleton in world frame
zed_interfaces/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