Main Content

PointCloud2

Access point cloud messages

Since R2019b

Description

The PointCloud2 object is an implementation of the sensor_msgs/PointCloud2 message type in ROS. The object contains meta-information about the message and the point cloud data. To access the actual data, use readXYZ to get the point coordinates and readRGB to get the color information, if available.

Creation

Description

example

ptcloud = rosmessage('sensor_msgs/PointCloud2') creates an empty PointCloud2 object. To specify point cloud data, use the ptcloud.Data property. You can also get point cloud data messages off the ROS network using rossubscriber.

Properties

expand all

This property is read-only.

Preserve the shape of point cloud matrix, specified as false or true. When the property is true, the output data from readXYZ and readRGB are returned as matrices instead of vectors.

This property is read-only.

Message type of ROS message, returned as a character vector.

Data Types: char

This property is read-only.

ROS Header message, returned as a Header object. This header message contains the MessageType, sequence (Seq), timestamp (Stamp), and FrameId.

Point cloud height in pixels, specified as an integer.

Point cloud width in pixels, specified as an integer.

Image byte sequence, specified as true or false.

  • true —Big endian sequence. Stores the most significant byte in the smallest address.

  • false —Little endian sequence. Stores the least significant byte in the smallest address.

Length of a point in bytes, specified as an integer.

Full row length in bytes, specified as an integer. The row length equals the PointStep property multiplied by the Width property.

Point cloud data, specified as a uint8 array. To access the data, use the Object Functions.

Object Functions

readAllFieldNamesGet all available field names from ROS point cloud
readFieldRead point cloud data based on field name
readRGBExtract RGB values from point cloud data
readXYZExtract XYZ coordinates from point cloud data
scatter3Display point cloud in scatter plot
showdetailsDisplay all ROS message contents

Examples

collapse all

Access and visualize the data inside a point cloud message.

Create sample ROS messages and inspect a point cloud image. ptcloud is a sample ROS PointCloud2 message object.

exampleHelperROSLoadMessages
ptcloud
ptcloud = 
  ROS PointCloud2 message with properties:

    PreserveStructureOnRead: 0
                MessageType: 'sensor_msgs/PointCloud2'
                     Header: [1x1 Header]
                     Fields: [4x1 PointField]
                     Height: 480
                      Width: 640
                IsBigendian: 0
                  PointStep: 32
                    RowStep: 20480
                       Data: [9830400x1 uint8]
                    IsDense: 0

  Use showdetails to show the contents of the message

Get RGB info and xyz-coordinates from the point cloud using readXYZ and readRGB.

xyz = readXYZ(ptcloud);
rgb = readRGB(ptcloud);

Display the point cloud in a figure using scatter3.

scatter3(ptcloud)

Figure contains an axes object. The axes object with title Point Cloud, xlabel X, ylabel Y contains an object of type scatter.

Convert a ROS Toolbox™ point cloud message into a Computer Vision System Toolbox™ pointCloud object.

Load sample messages.

exampleHelperROSLoadMessages

Convert a ptcloud message to the pointCloud object.

pcobj = pointCloud(readXYZ(ptcloud),'Color',uint8(255*readRGB(ptcloud)))
pcobj = 
  pointCloud with properties:

     Location: [307200x3 single]
        Count: 307200
      XLimits: [-1.8147 1.1945]
      YLimits: [-1.3714 0.8812]
      ZLimits: [1.4190 3.3410]
        Color: [307200x3 uint8]
       Normal: []
    Intensity: []

Version History

Introduced in R2019b