Main Content

rosWriteXYZ

Write data points in x, y and z coordinates to a ROS or ROS 2 PointCloud2 message structure

Since R2023a

Description

msgOut = rosWriteXYZ(msgIn,xyz) writes the [x y z] coordinates 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 = rosWriteXYZ(msgIn,xyz,Name=Value) specifies additional options using one or more name-value arguments.

Examples

collapse all

This example shows how to write data points in x,y and z coordinates to a ROS or ROS 2 PointCloud2 message structure.

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

xyz = uint8(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. As x, y and z are of data type uint8, the PointStep is 3 bytes.

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

Now create a sensor_msgs/PointCloud2 message in ROS network to set the PointStep to the desired value.

emptyRosMsg = rosmessage("sensor_msgs/PointCloud2","DataFormat","struct");

Set the PointStep in sensor_msgs/PointCloud2 message to 32 to store remaining bytes with RGB or intensity data or both.

rosMsg = rosWriteXYZ(emptyRosMsg,xyz,"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

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

ros2Msg = ros2message("sensor_msgs/PointCloud2")
ros2Msg = struct with fields:
     MessageType: 'sensor_msgs/PointCloud2'
          header: [1x1 struct]
          height: 0
           width: 0
          fields: [1x1 struct]
    is_bigendian: 0
      point_step: 0
        row_step: 0
            data: 0
        is_dense: 0

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

ros2Msg = rosWriteXYZ(ros2Msg,xyz,"PointStep",32)
ros2Msg = struct with fields:
     MessageType: 'sensor_msgs/PointCloud2'
          header: [1x1 struct]
          height: 128
           width: 128
          fields: [3x1 struct]
    is_bigendian: 0
      point_step: 32
        row_step: 4096
            data: [524288x1 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 XYZ values, specified as a m-by-3 or m-by-n-by-3 matrix.

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

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 = rosWriteXYZ(msgIn,xyz,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 = rosWriteXYZ(msgIn,xyz,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