Main Content

rosWriteRGB

Write RGB color information to a ROS or ROS 2 PointCloud2 message structure

Since R2023a

Description

msgOut = rosWriteRGB(msgIn,rgb) writes the [r g b] values from m-by-3 matrix or m-by-n-by-3 matrix of 3-D point to a ROS or ROS 2 sensor_msgs/PointCloud2 message msgIn and stores the data points in the message msgOut.

example

msgOut = rosWriteRGB(msgIn,rgb,Name=Value) specifies additional options using one or more name-value arguments.

Examples

collapse all

This example shows how to write RGB color information to a ROS or ROS 2 PointCloud2 message structure. To write RGB data points to a ROS or ROS 2 PointCloud2 message, you must write x,y and z data points first.

Create a random m-by-n-by-3 matrix with x, y and z coordinate points.

xyzPoints = single(10*rand(128,128,3));

Create a sensor_msgs/PointCloud2 message in ROS network.

rosMsg = rosmessage("sensor_msgs/PointCloud2","DataFormat","struct")
rosMsg = struct with fields:
    MessageType: 'sensor_msgs/PointCloud2'
         Header: [1x1 struct]
         Height: 0
          Width: 0
         Fields: [0x1 struct]
    IsBigendian: 0
      PointStep: 0
        RowStep: 0
           Data: [0x1 uint8]
        IsDense: 0

Write the x, y and z coordinate points to the ROS message and set PointStep of sensor_msgs/PointCloud2 to 32 to store the RGB data points.

rosMsg = rosWriteXYZ(rosMsg,xyzPoints,"PointStep",32)
rosMsg = struct with fields:
    MessageType: 'sensor_msgs/PointCloud2'
         Header: [1x1 struct]
         Height: 128
          Width: 128
         Fields: [3x1 struct]
    IsBigendian: 0
      PointStep: 32
        RowStep: 4096
           Data: [524288x1 uint8]
        IsDense: 1

Create a random m-by-n-by-3 matrix with RGB values.

rgb = single(10*rand(128,128,3));

Write the RGB color information to the ROS message and set the offset of the RGB field in sensor_msgs/PointField to 16. This means that RGB field begins to be stored from 16th byte for each PointStep.

rosMsg = rosWriteRGB(rosMsg,rgb,"FieldOffset",16)
rosMsg = struct with fields:
    MessageType: 'sensor_msgs/PointCloud2'
         Header: [1x1 struct]
         Height: 128
          Width: 128
         Fields: [4x1 struct]
    IsBigendian: 0
      PointStep: 32
        RowStep: 4096
           Data: [524288x1 uint8]
        IsDense: 1

You can also create a sensor_msgs/PointCloud2 message in ROS 2 network.

ros2Msg = ros2message("sensor_msgs/PointCloud2");

Write the x, y and z coordinate points to the ROS 2 message. Set PointStep to 16.

ros2Msg = rosWriteXYZ(ros2Msg,xyzPoints,"PointStep",16)
ros2Msg = struct with fields:
     MessageType: 'sensor_msgs/PointCloud2'
          header: [1x1 struct]
          height: 128
           width: 128
          fields: [3x1 struct]
    is_bigendian: 0
      point_step: 16
        row_step: 2048
            data: [262144x1 uint8]
        is_dense: 1

Write the RGB color information to the ROS 2 message and set FieldOffset to 8.

ros2Msg = rosWriteRGB(ros2Msg,rgb,"FieldOffset",8)
ros2Msg = struct with fields:
     MessageType: 'sensor_msgs/PointCloud2'
          header: [1x1 struct]
          height: 128
           width: 128
          fields: [4x1 struct]
    is_bigendian: 0
      point_step: 16
        row_step: 2048
            data: [262144x1 uint8]
        is_dense: 1

Input Arguments

collapse all

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

Data Types: struct

List of RGB values, specified as a m-by-3 or m-by-n-by-3 matrix.

Data Types: single | double | int32 | uint8 | uint16 | uint32

Name-Value Arguments

Example: PointStep=pointstep

Point step is number of bytes or data entries for one point. If the PointStep field is not set in the input 'sensor_msgs/PointCloud2' message, you can use this parameter to manually set the PointStep information.

Example: msgOut = rosWriteIntensity(msgIn,rgb,PointStep=pointstep)

Data Types: uint32

Field Offset is number of bytes from the start of the point to the byte in which the field begins to be stored. If the offset field is not set for a PointField in the input 'sensor_msgs/PointCloud2' message, you can use this parameter to manually set the offset information.

Example: msgOut = rosWriteRGB(msgIn,rgb,FieldOffset=fieldoffset)

Data Types: uint32

Output Arguments

collapse all

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

Data Types: struct

Extended Capabilities

Version History

Introduced in R2023a