Some commonly used ROS messages store data in a format that requires some transformation before it can be used for further processing. MATLAB® can help you by formatting these specialized ROS messages for easy use. In this example, you can explore how message types for laser scans, uncompressed and compressed images, and point clouds are handled.
Prerequisites: Work with Basic ROS Messages
Load some sample messages. These messages are populated with data gathered from various robotics sensors.
exampleHelperROSLoadMessages
Laser scanners are commonly used sensors in robotics. You can see the standard ROS format for a laser scan message by creating an empty message of the appropriate type.
Use rosmessage
to create the message.
emptyscan = rosmessage('sensor_msgs/LaserScan')
emptyscan = ROS LaserScan message with properties: MessageType: 'sensor_msgs/LaserScan' Header: [1x1 Header] AngleMin: 0 AngleMax: 0 AngleIncrement: 0 TimeIncrement: 0 ScanTime: 0 RangeMin: 0 RangeMax: 0 Ranges: [0x1 single] Intensities: [0x1 single] Use showdetails to show the contents of the message
Since you created an empty message, emptyscan
does not contain any meaningful data. For convenience, the exampleHelperROSLoadMessages
function loaded a laser scan message that is fully populated and is stored in the scan
variable.
Inspect the scan
variable. The primary data in the message is in the Ranges
property. The data in Ranges
is a vector of obstacle distances recorded at small angle increments.
scan
scan = ROS LaserScan message with properties: MessageType: 'sensor_msgs/LaserScan' Header: [1x1 Header] AngleMin: -0.5467 AngleMax: 0.5467 AngleIncrement: 0.0017 TimeIncrement: 0 ScanTime: 0.0330 RangeMin: 0.4500 RangeMax: 10 Ranges: [640x1 single] Intensities: [0x1 single] Use showdetails to show the contents of the message
You can get the measured points in Cartesian coordinates using the readCartesian
function.
xy = readCartesian(scan);
This populates xy
with a list of [x,y]
coordinates that were calculated based on all valid range readings. Visualize the scan message using the plot
function:
figure
plot(scan,'MaximumRange',5)
MATLAB also provides support for image messages, which always have the message type sensor_msgs/Image
.
Create an empty image message using rosmessage
to see the standard ROS format for an image message.
emptyimg = rosmessage('sensor_msgs/Image')
emptyimg = ROS Image message with properties: MessageType: 'sensor_msgs/Image' Header: [1x1 Header] Height: 0 Width: 0 Encoding: '' IsBigendian: 0 Step: 0 Data: [0x1 uint8] Use showdetails to show the contents of the message
For convenience, the exampleHelperROSLoadMessages
function loaded an image message that is fully populated and is stored in the img
variable.
Inspect the image message variable img
in your workspace. The size of the image is stored in the Width
and Height
properties. ROS sends the actual image data using a vector in the Data
property.
img
img = ROS Image message with properties: MessageType: 'sensor_msgs/Image' Header: [1x1 Header] Height: 480 Width: 640 Encoding: 'rgb8' IsBigendian: 0 Step: 1920 Data: [921600x1 uint8] Use showdetails to show the contents of the message
The Data
property stores raw image data that cannot be used directly for processing and visualization in MATLAB. You can use the readImage
function to retrieve the image in a format that is compatible with MATLAB.
imageFormatted = readImage(img);
The original image has an 'rgb8' encoding. By default, readImage
returns the image in a standard 480-by-640-by-3 uint8
format. View this image using the imshow
function.
figure imshow(imageFormatted)
MATLAB® supports all ROS image encoding formats, and readImage
handles the complexity of converting the image data. In addition to color images, MATLAB also supports monochromatic and depth images.
Many ROS systems send their image data in a compressed format. MATLAB provides support for these compressed image messages.
Create an empty compressed image message using rosmessage
. Compressed images in ROS have the message type sensor_msgs/CompressedImage
and have a standard structure.
emptyimgcomp = rosmessage('sensor_msgs/CompressedImage')
emptyimgcomp = ROS CompressedImage message with properties: MessageType: 'sensor_msgs/CompressedImage' Header: [1x1 Header] Format: '' Data: [0x1 uint8] Use showdetails to show the contents of the message
For convenience, the exampleHelperROSLoadMessages
function loaded a compressed image message that is already populated.
Inspect the imgcomp
variable that was captured by a camera. The Format
property captures all the information that MATLAB needs to decompress the image data stored in Data
.
imgcomp
imgcomp = ROS CompressedImage message with properties: MessageType: 'sensor_msgs/CompressedImage' Header: [1x1 Header] Format: 'bgr8; jpeg compressed bgr8' Data: [30376x1 uint8] Use showdetails to show the contents of the message
Similar to the image message, you can use readImage
to obtain the image in standard RGB format. Even though the original encoding for this compressed image is bgr8
, readImage
the conversion.
compressedFormatted = readImage(imgcomp);
Visualize the image using the imshow
function.
figure imshow(compressedFormatted)
Most image formats are supported for the compressed image message type. The 16UC1
and 32FC1
encodings are not supported for compressed depth images. Monochromatic and color image encodings are supported.
Point clouds can be captured by a variety of sensors used in robotics, including LIDARs, Kinect®, and stereo cameras. The most common message type in ROS for transmitting point clouds is sensor_msgs/PointCloud2
and MATLAB provides some specialized functions for you to work with this data.
You can see the standard ROS format for a point cloud message by creating an empty point cloud message.
emptyptcloud = rosmessage('sensor_msgs/PointCloud2')
emptyptcloud = ROS PointCloud2 message with properties: PreserveStructureOnRead: 0 MessageType: 'sensor_msgs/PointCloud2' Header: [1x1 Header] Fields: [0x1 PointField] Height: 0 Width: 0 IsBigendian: 0 PointStep: 0 RowStep: 0 Data: [0x1 uint8] IsDense: 0 Use showdetails to show the contents of the message
View the populated point cloud message that is stored in the ptcloud
variable in your workspace:
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
The point cloud information is encoded in the Data
property of the message. You can extract the x,
y,
z coordinates as an N-by-3 matrix by calling the readXYZ
function.
xyz = readXYZ(ptcloud)
xyz = 307200x3 single matrix
NaN NaN NaN
NaN NaN NaN
NaN NaN NaN
NaN NaN NaN
NaN NaN NaN
NaN NaN NaN
NaN NaN NaN
NaN NaN NaN
NaN NaN NaN
NaN NaN NaN
⋮
NaN
in the point cloud data indicates that some of the x,
y,
z values are not valid. This is an artifact of the Kinect® sensor, and you can safely remove all NaN
values.
xyzvalid = xyz(~isnan(xyz(:,1)),:)
xyzvalid = 193359x3 single matrix
0.1378 -0.6705 1.6260
0.1409 -0.6705 1.6260
0.1433 -0.6672 1.6180
0.1464 -0.6672 1.6180
0.1502 -0.6705 1.6260
0.1526 -0.6672 1.6180
0.1556 -0.6672 1.6180
0.1587 -0.6672 1.6180
0.1618 -0.6672 1.6180
0.1649 -0.6672 1.6180
⋮
Some point cloud sensors also assign RGB color values to each point in a point cloud. If these color values exist, you can retrieve them with a call to readRGB
.
rgb = readRGB(ptcloud)
rgb = 307200×3
0.8392 0.7059 0.5255
0.8392 0.7059 0.5255
0.8392 0.7137 0.5333
0.8392 0.7216 0.5451
0.8431 0.7137 0.5529
0.8431 0.7098 0.5569
0.8471 0.7137 0.5569
0.8549 0.7098 0.5569
0.8588 0.7137 0.5529
0.8627 0.7137 0.5490
⋮
You can visualize the point cloud with the scatter3
function. scatter3
automatically extracts the x,
y,
z coordinates and the RGB color values (if they exist) and show them in a 3-D scatter plot. The scatter3
function ignores all NaN
x,
y,
z coordinates, even if RGB values exist for that point.
figure scatter3(ptcloud)