Main Content

rosReadField

Read point cloud data from ROS or ROS 2 message structure based on field name

Since R2021a

Description

fielddata = rosReadField(pcloud,fieldname) reads the point field from the ROS or ROS 2 'sensor_msgs/PointCloud2' message structure, pcloud, specified by fieldname and returns it in fielddata.

fielddata = rosReadField(pcloud,fieldname,"PreserveStructureOnRead",true) preserves the organizational structure of the point cloud field data returned in the fielddata output. For more information, see Preserving Point Cloud Structure.

fielddata = rosReadField(pcloud,fieldname,"Datatype","double") reads the point field 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

collapse all

Point cloud, specified as a message structure for ROS or ROS 2 'sensor_msgs/PointCloud2' message.

Field name of point cloud data, specified as a string scalar or character vector. This string must match the field name exactly. If fieldname does not exist, the function displays an error.

Output Arguments

collapse all

List of field values from point cloud, returned as a matrix. Each row of the matrix is a point cloud reading, where n is the number of points and c is the number of values for each point.

If the PreserveStructureOnRead name-value pair argument is set to true, the points are returned as an h-by-w-by-c matrix.

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 rosReadField 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 = rosReadField(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