Main Content

rosReadRGB

Extract RGB color values from ROS or ROS 2 point cloud message structure

Since R2021a

Description

rgb = rosReadRGB(pcloud) extracts the [r g b] values 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.

rgb = rosReadRGB(pcloud,"PreserveStructureOnRead",true) preserves the organizational structure of the point cloud returned in the rgb output. For more information, see Preserving Point Cloud Structure.

fielddata = rosReadRGB(pcloud,"Datatype","double") reads the [r g b] 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.

Output Arguments

collapse all

List of RGB values from point cloud, returned as a matrix. By default, this is a n-by-3 matrix.

If the PreserveStructureOnRead name-value pair argument is set to true, the points are returned as an h-by-w-by-3 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 rosReadRGB 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 = rosReadRGB(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