Improve Performance of ROS Using Message Structures
This example demonstrates the use of ROS message structures, and their benefits and differences from message objects.
Message structures have better performance over objects when performing initial creation, reading them from rosbag files, accessing nested properties, and performing communication operations over the ROS network. Also, message structures are the only supported message format when generating code through MATLAB Coder™.
Message Structure Basics
ROS message objects are instances of classes defined specifically for each message type.
msgObj = rosmessage("nav_msgs/Path");
class(msgObj)
ans = 'ros.msggen.nav_msgs.Path'
The object properties contain the data of the message, and each object type has functions defined that are specific to the ROS message.
showdetails(msgObj)
Header Stamp Sec : 0 Nsec : 0 Seq : 0 FrameId : Poses
ROS message structures have been introduced to improve the performance of using ROS messages. Each message is a MATLAB® structure data type with the same fields as the properties of the ROS message objects.
msgStruct = rosmessage("nav_msgs/Path","DataFormat","struct")
msgStruct = struct with fields:
MessageType: 'nav_msgs/Path'
Header: [1×1 struct]
Poses: [0×1 struct]
class(msgStruct)
ans = 'struct'
Update Existing Code to Use Structures
To update existing code that uses objects, two common workflows are provided with the steps required to update them.
Communication Workflow
This example code shows how to send and receive messages over the ROS network.
% Setup ROS network
rosinit
Launching ROS Core... .......Done in 7.8277 seconds. Initializing ROS master on http://172.21.16.85:56827. Initializing global node /matlab_global_node_64123 with NodeURI http://ah-avijayar:57735/ and MasterURI http://localhost:56827.
stringPub = rospublisher("/chatter","std_msgs/String"); stringSub = rossubscriber("/chatter","std_msgs/String"); % Set message field and send message stringMsg = rosmessage("std_msgs/String"); stringMsg.Data = 'Hello World!'; send(stringPub,stringMsg) % Wait for message to be received and then check the value pause(2) showdetails(stringSub.LatestMessage)
Data : Hello World!
How to Update
Set the data format name-value argument of the publisher and subscriber.
stringPub = rospublisher("/chatter","std_msgs/String","DataFormat","struct"); stringSub = rossubscriber("/chatter","std_msgs/String","DataFormat","struct");
Update the data format for the rosmessage
function as well.
stringMsg = rosmessage("std_msgs/String","DataFormat","struct"); stringMsg.Data = 'Hello World!'; send(stringPub,stringMsg)
Alternatively, the rosmessage
object function for the publisher can be used. This syntax produces a message that follows the format set in the publisher, and is the most efficient way to ensure compatibility between the message and the publisher.
stringMsg = rosmessage(stringPub);
stringMsg.Data = 'Hello World!';
send(stringPub,stringMsg)
Because structures do not have object functions, new functions are provided to handle common ROS message tasks. To show details a structure message, use the rosShowDetails
function. To see all the new functions provided, go to Message Handling Functions.
% Wait for message to be received and then check the value
pause(2)
rosShowDetails(stringSub.LatestMessage)
ans = ' MessageType : std_msgs/String Data : Hello World!'
Read rosbag Workflow
For an example that reads messages from a rosbag
, specify the DataFormat
name-value argument for the readMessages
function and any publishers you use to send those messages.
% Extract message from rosbag msgType = "nav_msgs/Odometry"; bag = rosbag("ex_multiple_topics.bag"); bagSelect = select(bag,"MessageType",msgType); odomMsgs = readMessages(bagSelect,"DataFormat","struct"); odomMsg = odomMsgs{1}
odomMsg = struct with fields:
MessageType: 'nav_msgs/Odometry'
Header: [1×1 struct]
ChildFrameId: 'base_footprint'
Pose: [1×1 struct]
Twist: [1×1 struct]
% Create publisher and send first message odomPub = rospublisher("/odom",msgType,"DataFormat","struct"); send(odomPub,odomMsg)
Message Handling Functions
Because functions on the ROS message objects are not usable with message structures, new functions have been introduced for handling messages. This list includes functions for reading data from or writing data to specialized messages.
Behavior Changes
Handle Class vs. Structure Behavior
An important consideration when converting code is that ROS message objects are handles, which means that message objects are passed by reference when provided as inputs to functions. If a message is modified within a function, the modification applies to the message in the MATLAB® workspace as well.
msgObj = rosmessage("geometry_msgs/Pose2D");
pose = [1 2 3];
exampleHelperWritePoseToMsgObj(msgObj,pose)
disp(msgObj)
ROS Pose2D message with properties: MessageType: 'geometry_msgs/Pose2D' X: 1 Y: 2 Theta: 3 Use showdetails to show the contents of the message
function exampleHelperWritePoseToMsgObj(pointMsg,pose) pointMsg.X = pose(1); pointMsg.Y = pose(2); pointMsg.Theta = pose(3); end
Message structures only pass their value when input into functions. If a message structure is modified within a function, that modification will only apply to the structure within the scope of that function. To make the modification available outside of the function, the message structure must be returned.
msgStruct = rosmessage("geometry_msgs/Pose2D","DataFormat","struct"); pose = [1 2 3]; % With no return, the message structure will not change exampleHelperWritePoseToMsgObj(msgStruct, pose) disp(msgStruct)
MessageType: 'geometry_msgs/Pose2D' X: 0 Y: 0 Theta: 0
% When returned from the function, the message can be overwritten.
msgStruct = exampleHelperWritePoseToMsgStruct(msgStruct, pose);
disp(msgStruct)
MessageType: 'geometry_msgs/Pose2D' X: 1 Y: 2 Theta: 3
function pointMsg = exampleHelperWritePoseToMsgStruct(pointMsg,pose) pointMsg.X = pose(1); pointMsg.Y = pose(2); pointMsg.Theta = pose(3); end
This applies to the specialized message handling functions as well. The write functions that update message values now have output arguments to supply the updated message structure.
image = imread('imageMap.png'); % Message object msg = rosmessage("sensor_msgs/Image"); msg.Encoding = 'rgb8'; writeImage(msg,image) imshow(readImage(msg))
% Message structure msg = rosmessage("sensor_msgs/Image","DataFormat","struct"); msg.Encoding = 'rgb8'; msg = rosWriteImage(msg,image); imshow(rosReadImage(msg)) close
Time and Duration Arithmatic
ROS time and duration message structures are unable to support operator overloading in the same way that the time and duration objects do. Arithmetic and comparison operations should be done by converting the time or duration structures to a numerical seconds value, performing the operation, and then recreating the time or duration structure if necessary.
% Periodically update message timestamp with objects msg = rosmessage("std_msgs/Header"); runFor = rosduration(2); tNow = rostime("now"); tEnd = tNow + runFor; while tNow < tEnd msg.Stamp = tNow; % Message may be sent here pause(1) tNow = rostime("now"); end % Periodically update message timestamp with structures msg = rosmessage("std_msgs/Header","DataFormat","struct"); runFor = 2; tNow = rostime("now","DataFormat","struct"); tNowSec = tNow.Sec + tNow.Nsec*1e-9; tEndSec = tNowSec + runFor; while tNowSec < tEndSec msg.Stamp = tNow; % Message may be sent here pause(1) tNow = rostime("now","DataFormat","struct"); tNowSec = tNow.Sec + tNow.Nsec*1e-9; end
Data Field Coercion
With ROS message objects, data fields have specific types. When a data field value is set, the input is converted to the correct type if possible. Otherwise, if conversion is not possible, an error is returned.
msg = rosmessage("std_msgs/Int8");
msg.Data = 20;
class(msg.Data)
ans = 'int8'
ROS message structures inherently accept any data type or field name without error.
msg = rosmessage("std_msgs/Int8","DataFormat","struct"); msg.Data = 'Test'
msg = struct with fields:
MessageType: 'std_msgs/Int8'
Data: 'Test'
msg.Data = 20; class(msg.Data)
ans = 'double'
Instead, invalid data types error when attempting to send the message over the ROS network.
pub = rospublisher("/int_topic","std_msgs/Int8","DataFormat","struct"); send(pub,msg)
Error using ros.Publisher/send (line 290) Error publishing a message with type std_msgs/Int8 on topic name /int_topic. Caused by: Error using ros.internal.Node/publish Field 'Data' is wrong type; expected a int8.
To prevent errors, ensure that messages are using the correct data type from the message definition.
rosmsg show std_msgs/Int8
int8 Data
Other Performance Tips
Using message structures is a good first step to speed up the sending and retrieving of ROS messages. Structures also improves the performance for setting and accessing data in nested mesages.The following code demonstrates sending multiple messages with nested fields.
% Set up network (reuse publisher for all examples) pub = rospublisher("/goal_path","nav_msgs/Path","DataFormat","struct"); % Send robot new paths to follow nPtsOnPath = 100; for iPaths = 1:15 pathMsg = rosmessage(pub); for iPts = 1:nPtsOnPath pathMsg.Poses(iPts) = rosmessage("geometry_msgs/PoseStamped","DataFormat","struct"); pathMsg.Poses(iPts).Pose.Position.X = iPaths+iPts; pathMsg.Poses(iPts).Pose.Position.Y = iPaths-iPts; pathMsg.Poses(iPts).Pose.Position.Z = (iPaths+iPts)/10; end send(pub,pathMsg) end
Reuse Messages
If messages are being created and modified in a loop, and the same data fields are being set each iteration, it is faster to create the message only once. Move the creation of the messages outside the loop, and reuse the same messages inside the loop for each iteration.
% Set up messages for use pathMsg = rosmessage(pub); poseMsg = rosmessage("geometry_msgs/PoseStamped","DataFormat","struct"); % Send robot new paths to follow nPtsOnPath = 100; for iPaths = 1:15 for iPts = 1:nPtsOnPath pathMsg.Poses(iPts) = poseMsg; pathMsg.Poses(iPts).Pose.Position.X = iPaths+iPts; pathMsg.Poses(iPts).Pose.Position.Y = iPaths-iPts; pathMsg.Poses(iPts).Pose.Position.Z = (iPaths+iPts)/10; end send(pub,pathMsg) end
Extract Nested Messages for Manipulation
When reading or setting multiple fields in a nested message, extract the nested message before reading or setting the fields.
% Set up messages for use pathMsg = rosmessage(pub); poseMsg = rosmessage("geometry_msgs/PoseStamped","DataFormat","struct"); ptMsg = poseMsg.Pose.Position; % Extract nested message % Send robot new paths to follow nPtsOnPath = 100; for iPaths = 1:15 for iPts = 1:nPtsOnPath % Set fields before setting nested message ptMsg.X = iPaths+iPts; ptMsg.Y = iPaths-iPts; ptMsg.Z = (iPaths+iPts)/10; poseMsg.Pose.Position = ptMsg; pathMsg.Poses(iPts) = poseMsg; end send(pub,pathMsg) end
Preallocate Message Struct Arrays
For relatively large arrays of messages, preallocating a structure array can improve performance when setting values in a loop. Use this method when the array is a fixed length every iteration.
% Set up messages for use pathMsg = rosmessage(pub); poseMsg = rosmessage("geometry_msgs/PoseStamped","DataFormat","struct"); ptMsg = poseMsg.Pose.Position; % Extract nested message % Preallocate path array nPtsOnPath = 100; pathMsg.Poses(nPtsOnPath) = poseMsg; % Send robot new paths to follow for iPaths = 1:15 for iPts = 1:nPtsOnPath % Set fields before setting nested message ptMsg.X = iPaths+iPts; ptMsg.Y = iPaths-iPts; ptMsg.Z = (iPaths+iPts)/10; poseMsg.Pose.Position = ptMsg; pathMsg.Poses(iPts) = poseMsg; end send(pub,pathMsg) end
The ROS network can now be shut down.
rosshutdown
Shutting down global node /matlab_global_node_64123 with NodeURI http://ah-avijayar:57735/ and MasterURI http://localhost:56827. Shutting down ROS master on http://172.21.16.85:56827.