Messages are the primary container for exchanging data in ROS. Topics and services use messages to carry data between nodes. (See Exchange Data with ROS Publishers and Subscribers and Call and Provide ROS Services for more information on topics and services)
To identify its data structure, each message has a message type. For example, sensor data from a laser scanner is typically sent in a message of type sensor_msgs/LaserScan
. Each message type identifies the data elements that are contained in a message. Every message type name is a combination of a package name, followed by a forward slash /, and a type name:
MATLAB® supports many ROS message types that are commonly encountered in robotics applications. This example shows some of the ways to create, explore, and populate ROS messages in MATLAB.
Prerequisites: Get Started with ROS, Connect to a ROS Network
Initialize the ROS master and global node.
rosinit
Initializing ROS master on http://bat6346glnxa64:44409/. Initializing global node /matlab_global_node_77793 with NodeURI http://bat6346glnxa64:36993/
Use exampleHelperROSCreateSampleNetwork
to populate the ROS network with three additional nodes and sample publishers and subscribers.
exampleHelperROSCreateSampleNetwork
There are various nodes on the network with a few topics and affiliated publishers and subscribers.
You can see the full list of available topics by calling rostopic
list
.
rostopic list
/pose /rosout /scan
If you want to know more about the type of data that is sent through the /scan
topic, use the rostopic info
command to examine it. /scan
has a message type of sensor_msgs/LaserScan
.
rostopic info /scan
Type: sensor_msgs/LaserScan Publishers: * /node_3 (http://bat6346glnxa64:37145/) Subscribers: * /node_2 (http://bat6346glnxa64:46725/) * /node_1 (http://bat6346glnxa64:32831/)
The command output also tells you which nodes are publishing and subscribing to the topic. To learn about publishers and subscribers, see Call and Provide ROS Services.
To find out more about the topic's message type, create an empty message of the same type using the rosmessage
function. rosmessage
supports tab completion for the message type. To complete message type names, type the first few characters of the name you want to complete, and then press the Tab key.
scandata = rosmessage('sensor_msgs/LaserScan')
scandata = 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
The created message scandata
has many properties associated with data typically received from a laser scanner. For example, the minimum sensing distance is stored in the RangeMin
property, and the maximum sensing distance is in RangeMax
.
To see a complete list of all message types available for topics and services, use rosmsg
list
.
ROS messages are objects, and the message data is stored in properties. MATLAB features convenient ways to find and explore the contents of messages.
If you subscribe to the /pose
topic, you can receive and examine the messages that are sent.
posesub = rossubscriber('/pose')
posesub = Subscriber with properties: TopicName: '/pose' MessageType: 'geometry_msgs/Twist' LatestMessage: [0x1 Twist] BufferSize: 1 NewMessageFcn: []
Use receive
to get data from the subscriber. Once a new message is received, the function will return it and store it in the posedata
variable (the second argument is a time-out in seconds).
posedata = receive(posesub, 10)
posedata = ROS Twist message with properties: MessageType: 'geometry_msgs/Twist' Linear: [1x1 Vector3] Angular: [1x1 Vector3] Use showdetails to show the contents of the message
The message has a type of geometry_msgs/Twist
. There are two other properties in the message: Linear
and Angular
. You can see the values of these message properties by accessing them directly:
posedata.Linear
ans = ROS Vector3 message with properties: MessageType: 'geometry_msgs/Vector3' X: 0.0315 Y: 0.0406 Z: -0.0373 Use showdetails to show the contents of the message
posedata.Angular
ans = ROS Vector3 message with properties: MessageType: 'geometry_msgs/Vector3' X: 0.0413 Y: 0.0132 Z: -0.0402 Use showdetails to show the contents of the message
Each of the values of these message fields is actually a message in itself. The message type for these is geometry_msgs/Vector3
. geometry_msgs/Twist
is a composite message made up of two geometry_msgs/Vector3
messages.
Data access for these nested messages works exactly the same as accessing the data in other messages. Access the X
component of the Linear
message using this command:
xpos = posedata.Linear.X
xpos = 0.0315
If you want a quick summary of all the data contained in a message, call the showdetails
function. showdetails
works on messages of any type and recursively displays all the message data properties.
showdetails(posedata)
Linear X : 0.03147236863931789 Y : 0.04057919370756193 Z : -0.03730131837064939 Angular X : 0.04133758561390194 Y : 0.01323592462254095 Z : -0.04024595950005905
showdetails
helps you during debugging and when you want to quickly explore the contents of a message.
You can also set message property values. Create a message with type geometry_msgs/Twist
.
twist = rosmessage('geometry_msgs/Twist')
twist = ROS Twist message with properties: MessageType: 'geometry_msgs/Twist' Linear: [1x1 Vector3] Angular: [1x1 Vector3] Use showdetails to show the contents of the message
The numeric properties of this message are initialized to 0
by default. You can modify any of the properties of this message. Set the Linear.Y
entry equal to 5
.
twist.Linear.Y = 5;
View the message data to make sure that your change took effect.
twist.Linear
ans = ROS Vector3 message with properties: MessageType: 'geometry_msgs/Vector3' X: 0 Y: 5 Z: 0 Use showdetails to show the contents of the message
Once a message is populated with your data, you can use it with publishers, subscribers, and services. See the Exchange Data with ROS Publishers and Subscribers and Call and Provide ROS Services examples.
There are two ways to copy the contents of a message:
You can create a reference copy and the original messages share the same data.
You can create a deep copy. The deep copy in which the copy and the original messages each have their own data.
A reference copy is useful if you want to share message data between different functions or objects, whereas a deep copy is necessary if you want an independent copy of a message.
Make a reference copy of a message by using the =
sign. This creates a variable that references the same message contents as the original variable.
twistCopyRef = twist
twistCopyRef = ROS Twist message with properties: MessageType: 'geometry_msgs/Twist' Linear: [1x1 Vector3] Angular: [1x1 Vector3] Use showdetails to show the contents of the message
Modify the Linear.Z
field of twistCopyRef
. This also changes the contents of twist.
twistCopyRef.Linear.Z = 7; twist.Linear
ans = ROS Vector3 message with properties: MessageType: 'geometry_msgs/Vector3' X: 0 Y: 5 Z: 7 Use showdetails to show the contents of the message
Make a deep copy of twist
so that you can change its contents without affecting the original data. Make a new message, twistCopyDeep
, using the copy
function:
twistCopyDeep = copy(twist)
twistCopyDeep = ROS Twist message with properties: MessageType: 'geometry_msgs/Twist' Linear: [1x1 Vector3] Angular: [1x1 Vector3] Use showdetails to show the contents of the message
Modify the Linear.X
property of twistCopyDeep
. The contents of twist
remain unchanged.
twistCopyDeep.Linear.X = 100; twistCopyDeep.Linear
ans = ROS Vector3 message with properties: MessageType: 'geometry_msgs/Vector3' X: 100 Y: 5 Z: 7 Use showdetails to show the contents of the message
twist.Linear
ans = ROS Vector3 message with properties: MessageType: 'geometry_msgs/Vector3' X: 0 Y: 5 Z: 7 Use showdetails to show the contents of the message
You can save messages and store the contents for later use.
Get a new message from the subscriber.
posedata = receive(posesub,10)
posedata = ROS Twist message with properties: MessageType: 'geometry_msgs/Twist' Linear: [1x1 Vector3] Angular: [1x1 Vector3] Use showdetails to show the contents of the message
Save the pose data to a MAT file using MATLAB's save
function.
save('posedata.mat','posedata')
Before loading the file back into the workspace, clear the posedata
variable.
clear posedata
Now you can load the message data by calling the load
function. This loads the posedata
from above into the messageData
structure. posedata
is a data field of the struct.
messageData = load('posedata.mat')
messageData = struct with fields:
posedata: [1x1 Twist]
Examine messageData.posedata
to see the message contents.
messageData.posedata
ans = ROS Twist message with properties: MessageType: 'geometry_msgs/Twist' Linear: [1x1 Vector3] Angular: [1x1 Vector3] Use showdetails to show the contents of the message
You can now delete the MAT file.
delete('posedata.mat')
Some messages from ROS are stored in Object Arrays (MATLAB). These must be handled differently from typical data arrays.
In your workspace, the variable tf
contains a sample message. (The exampleHelperROSCreateSampleNetwork
script created the variable.) In this case, it is a message of type tf/tfMessage
used for coordinate transformations.
tf
tf = ROS tfMessage message with properties: MessageType: 'tf/tfMessage' Transforms: [53x1 TransformStamped] Use showdetails to show the contents of the message
tf
has two fields: MessageType
contains a standard data array, and Transforms
contains an object array. There are 53 objects stored in Transforms
, and all of them have the same structure.
Expand tf
in Transforms
to see the structure:
tf.Transforms
ans = 53x1 ROS TransformStamped message array with properties: MessageType Header ChildFrameId Transform
Each object in Transforms
has four properties. You can expand to see the Transform
field of Transforms
.
tformFields = tf.Transforms.Transform
Note: The command output returns 53 individual answers, since each object is evaluated and returns the value of its Transform
field. This format is not always useful, so you can convert it to a cell array with the following command:
cellTransforms = {tf.Transforms.Transform}
cellTransforms=1×53 cell array
Columns 1 through 4
{1x1 Transform} {1x1 Transform} {1x1 Transform} {1x1 Transform}
Columns 5 through 8
{1x1 Transform} {1x1 Transform} {1x1 Transform} {1x1 Transform}
Columns 9 through 12
{1x1 Transform} {1x1 Transform} {1x1 Transform} {1x1 Transform}
Columns 13 through 16
{1x1 Transform} {1x1 Transform} {1x1 Transform} {1x1 Transform}
Columns 17 through 20
{1x1 Transform} {1x1 Transform} {1x1 Transform} {1x1 Transform}
Columns 21 through 24
{1x1 Transform} {1x1 Transform} {1x1 Transform} {1x1 Transform}
Columns 25 through 28
{1x1 Transform} {1x1 Transform} {1x1 Transform} {1x1 Transform}
Columns 29 through 32
{1x1 Transform} {1x1 Transform} {1x1 Transform} {1x1 Transform}
Columns 33 through 36
{1x1 Transform} {1x1 Transform} {1x1 Transform} {1x1 Transform}
Columns 37 through 40
{1x1 Transform} {1x1 Transform} {1x1 Transform} {1x1 Transform}
Columns 41 through 44
{1x1 Transform} {1x1 Transform} {1x1 Transform} {1x1 Transform}
Columns 45 through 48
{1x1 Transform} {1x1 Transform} {1x1 Transform} {1x1 Transform}
Columns 49 through 52
{1x1 Transform} {1x1 Transform} {1x1 Transform} {1x1 Transform}
Column 53
{1x1 Transform}
This puts all 53 object entries in a cell array, enabling you to access them with indexing.
In addition, you can access object array elements the same way you access standard MATLAB vectors:
tf.Transforms(5)
ans = ROS TransformStamped message with properties: MessageType: 'geometry_msgs/TransformStamped' Header: [1x1 Header] ChildFrameId: '/imu_link' Transform: [1x1 Transform] Use showdetails to show the contents of the message
Access the translation component of the fifth transform in the list of 53:
tf.Transforms(5).Transform.Translation
ans = ROS Vector3 message with properties: MessageType: 'geometry_msgs/Vector3' X: 0.0599 Y: 0 Z: -0.0141 Use showdetails to show the contents of the message
Remove the sample nodes, publishers, and subscribers from the ROS network.
exampleHelperROSShutDownSampleNetwork
Shut down the ROS master and delete the global node.
rosshutdown
Shutting down global node /matlab_global_node_77793 with NodeURI http://bat6346glnxa64:36993/ Shutting down ROS master on http://bat6346glnxa64:44409/.
See Work with Specialized ROS Messages for examples of handling images, point clouds, and laser scan messages.
For application examples, see the Get Started with Gazebo and a Simulated TurtleBot or Get Started with a Real TurtleBot examples.