Main Content

readRGB

Extract RGB values from point cloud data

Since R2019b

Description

example

rgb = readRGB(pcloud) extracts the [r g b] values from all points in the PointCloud2 object, pcloud, and returns them as an n-by-3 matrix of n 3-D point coordinates. If the point cloud does not contain the RGB field, this function displays an error. To preserve the structure of the point cloud data, see Preserving Point Cloud Structure.

Note

readRGB will be removed. Use rosReadRGB instead. For more information, see ROS Message Structure Functions

Examples

collapse all

Load sample ROS messages including a ROS point cloud message, ptcloud.

exampleHelperROSLoadMessages

Read the RGB values from the point cloud.

rgb = readRGB(ptcloud);

Input Arguments

collapse all

Point cloud, specified as a PointCloud2 object handle for a 'sensor_msgs/PointCloud2' ROS message.

Output Arguments

collapse all

List of RGB values from point cloud, returned as a matrix. By default, this is an n-by-3 matrix. If the point cloud object being read has the PreserveStructureOnRead property set to true, the points are returned as an h-by-w-by-3 matrix. For more information, see Preserving Point Cloud Structure.

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 input PointCloud2 object contains a PreserveStructureOnRead property that is either true or false (default). Suppose that you set the property to true.

pcloud.PreserveStructureOnRead = true;

Now calling any read functions (readXYZ,readRGB, or readField) preserves the organizational structure of the point cloud. 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 an x-by-d list. This structure can be preserved only if the point cloud is organized.

Version History

Introduced in R2019b

expand all