rosWriteIntensity
Write intensity data points to a ROS or ROS 2 PointCloud2 message structure
Since R2023a
Syntax
Description
specifies additional options using one or more name-value arguments.msgOut
= rosWriteIntensity(msgIn
,intensity
,Name=Value
)
Examples
Write Intensity Data Points to a ROS or ROS 2 PointCloud2 Message
This example shows how to write intensity data points to a ROS or ROS 2 PointCloud2 message structure. To write intensity 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(480,640,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 16 to store the intensity data points.
rosMsg = rosWriteXYZ(rosMsg,xyzPoints,"PointStep",16)
rosMsg = struct with fields:
MessageType: 'sensor_msgs/PointCloud2'
Header: [1x1 struct]
Height: 480
Width: 640
Fields: [3x1 struct]
IsBigendian: 0
PointStep: 16
RowStep: 10240
Data: [4915200x1 uint8]
IsDense: 1
Create a random m
-by-n
matrix with intensity values.
intensity = uint8(10*rand(480,640));
Write the intensity information to the ROS message and set the offset of the intensity field in sensor_msgs/PointField
to 8. This means that intensity field begins to be stored from 16th byte for each PointStep
.
rosMsg = rosWriteIntensity(rosMsg,intensity,"FieldOffset",8)
rosMsg = struct with fields:
MessageType: 'sensor_msgs/PointCloud2'
Header: [1x1 struct]
Height: 480
Width: 640
Fields: [4x1 struct]
IsBigendian: 0
PointStep: 16
RowStep: 10240
Data: [4915200x1 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: 480
width: 640
fields: [3x1 struct]
is_bigendian: 0
point_step: 16
row_step: 10240
data: [4915200x1 uint8]
is_dense: 1
Write the intensity information to the ROS 2 message and set FieldOffset
to 8.
ros2Msg = rosWriteIntensity(ros2Msg,intensity,"FieldOffset",8)
ros2Msg = struct with fields:
MessageType: 'sensor_msgs/PointCloud2'
header: [1x1 struct]
height: 480
width: 640
fields: [4x1 struct]
is_bigendian: 0
point_step: 16
row_step: 10240
data: [4915200x1 uint8]
is_dense: 1
Input Arguments
msgIn
— PointCloud2
message
"struct"
PointCloud2
, specified as a structure for ROS or ROS 2
sensor_msgs/PointCloud2
message.
Data Types: struct
intensity
— List of intensity values
m-by-1 vector | m-by-n matrix
List of intensity values, specified as a m-by-1 vector or m-by-n matrix.
Data Types: single
| double
| int32
| uint8
| uint16
| uint32
Name-Value Arguments
Example: PointStep=pointstep
PointStep
— Provides optional parameter for setting up the point step value of the input
sensor_msgs/PointCloud2
message
uint32(0) (default)
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,intensity,PointStep=pointstep)
Data Types: uint32
FieldOffset
— provides optional parameter for setting up the offset of a PointField
of the input sensor_msgs/PointCloud2
message
uint32(0) (default)
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 =
rosWriteIntensity(msgIn,intensity,FieldOffset=fieldoffset)
Data Types: uint32
Output Arguments
msgOut
— PointCloud2
message
"struct"
PointCloud2
, specified as a structure for ROS or ROS 2
'sensor_msgs/PointCloud2'
message.
Data Types: struct
Extended Capabilities
C/C++ Code Generation
Generate C and C++ code using MATLAB® Coder™.
Usage notes and limitations:
Usage in MATLAB Function block is not supported.
Version History
Introduced in R2023a
MATLAB Command
You clicked a link that corresponds to this MATLAB command:
Run the command by entering it in the MATLAB Command Window. Web browsers do not support MATLAB commands.
Select a Web Site
Choose a web site to get translated content where available and see local events and offers. Based on your location, we recommend that you select: .
You can also select a web site from the following list
How to Get Best Site Performance
Select the China site (in Chinese or English) for best site performance. Other MathWorks country sites are not optimized for visits from your location.
Americas
- América Latina (Español)
- Canada (English)
- United States (English)
Europe
- Belgium (English)
- Denmark (English)
- Deutschland (Deutsch)
- España (Español)
- Finland (English)
- France (Français)
- Ireland (English)
- Italia (Italiano)
- Luxembourg (English)
- Netherlands (English)
- Norway (English)
- Österreich (Deutsch)
- Portugal (English)
- Sweden (English)
- Switzerland
- United Kingdom (English)
Asia Pacific
- Australia (English)
- India (English)
- New Zealand (English)
- 中国
- 日本Japanese (日本語)
- 한국Korean (한국어)