rosReadXYZ
Extract XYZ coordinates from ROS or ROS 2 point cloud message structure
Since R2021a
Syntax
Description
extracts the xyz
= rosReadXYZ(pcloud
)[x y z]
coordinates from all points in the ROS or
ROS 2 'sensor_msgs/PointCloud2'
message structure,
pcloud
, and returns them as an n-by-3
matrix of n 3-D point coordinates. If the point cloud does not
contain the x, y, and z
fields, this function returns an error. Points that contain NaN
are preserved in the output.
preserves the organizational structure of the point cloud returned in the
xyz
= rosReadXYZ(pcloud
,"PreserveStructureOnRead",true)xyz
output. For more information, see Preserving Point Cloud Structure.
fielddata = rosReadXYZ(pcloud,"Datatype","double")
reads the
[x y z]
data in double precision during code generation. If
you use this syntax for MATLAB® execution, the function always reads the data in the precision
specified by the corresponding field in the input message structure,
pcloud
.
Input Arguments
Output Arguments
Tips
Point cloud data can be organized in either 1-D lists or in 2-D image styles. 2-D
image styles usually come from depth sensors or stereo cameras. The
rosReadXYZ
function contains a
PreserveStructureOnRead
input Name,Value
argument that you can either set to true
or false
(default). If you set the argument to true
, the function preserves
the organizational structure of the point
cloud.
rgb = rosReadXYZ(pcloud,"PreserveStructureOnRead",true)
When you preserve the structure, the output matrices are of size m-by-n-by-d, where m is the height, n is the width, and d is the number of return values for each point. Otherwise, all points are returned as a x-by-d list. This structure can be preserved only if the point cloud is organized.
Extended Capabilities
Version History
Introduced in R2021a