Work with ROS 2 Messages in Simulink
This example illustrates how to work with complex ROS 2 messages in Simulink®, such as messages with nested sub-messages and variable-length arrays.
Introduction
In ROS 2 Simulink Models, bus signals represent ROS 2 Messages. Each field of a ROS 2 message is corresponds to a field in a Simulink bus, with the following limitations:
Constants are not supported, and are excluded from the Simulink bus.
Variable-length arrays (ROS type
...[]
) convert to fixed-length array with customizable maximum lengths. By default, the fixed length is 128 for primitive types (e.g.,uint8[]
,float32[]
), and 16 for nested arrays of messages (e.g.,geometry_msgs/Point[]
).Strings (ROS type
string
) convert to fixed-lengthuint8
arrays with customizable maximum lengths, with a default maximum length of 128 characters.String arrays (ROS type
string[]
) convert to a fixed-length array ofstd_msgs/String
with a customizable maximum length. The default maximum length is 16 strings.
When a Simulink bus converts to a ROS 2 message, the message fields restore to their native ROS 2 types. For example, the ROS message type std_msgs/Header
has a field, frame_id
, which is a string. In the corresponding Simulink bus, the frame_id
field is a uint8
array. When the bus converts to a ROS message, frame_id
converts back to a string.
Model
The following model has several examples of working with complex ROS 2 messages in Simulink. The rest of the tasks in this example focus on specific scenarios.
open_system('robotROS2MessageUsageExample');
Access Data in a Variable-length Array
A ROS 2 message can have arrays whose length (number of elements) cannot be pre-determined. For example, the position
field in a sensor_msgs/JointState
message is a variable-length array of 64-bit floats. In any given sensor_msgs/JointState
message, the position
array can have no elements or it can have an arbitrarily large number of elements. In Simulink, such arrays are required to have a maximum length.
Open the example model and explore how variable-length arrays in ROS messages are handled in Simulink in the following steps.
open_system('robotROS2MessageUsageExample/Work with Variable-length Arrays');
Double-click the Work with Variable-length Arrays subsystem. Note that the Subscribe block is configured to receive messages sent to topic
/my_joint_topic
as message type,sensor_msgs/JointState
.Under the Modeling tab, click Update Model.
Double-click on the Bus Selector block. There are three variable-length arrays in the message (
position
,velocity
, andeffort
).Observe that there is a p
osition_SL_Info
field in the bus. position_SL_Info.ReceivedLength
holds the length of thePosition
array in the original received ROS 2 message. This value can be arbitrarily large. position_SL_Info.CurrentLength
holds the length of the position
array in the Simulink bus signal. This can vary between 0 and the maximum length of the array (128, in this case).
Configure ROS 2 Network
Under the Simulation tab, select ROS Network from the Prepare section. If you do not see ROS Toolbox, select Robot Operating System (ROS) on the Apps tab, under Control Systems. In the dialog box that opens up, select Robot Operating System 2 (ROS 2) from the ROS Network drop-down.
Set the Domain ID and RMW Implementation to desired values.
Run Simulation
Under the Simulation tab, set Stop Time to
Inf
, and click Play to start simulation.Execute the following at the MATLAB command line.
node = ros2node("/my_node"); [pub, msg] = ros2publisher(node,"/my_joint_state", "sensor_msgs/JointState",Durability="transientlocal"); msg.position = [11:2:25]; % array of length 8 send(pub, msg);
Observe the Display outputs in the Work with Variable-length Arrays subsystem. Note that
Current
Length
andReceived
Length
are equal.Execute the following at the MATLAB command line.
msg.position = 1:130; % array of length 130
send(pub, msg);
Under the Debug tab, select Diagnostics > Diagnostic Viewer. Observe that a warning is emitted, indicating that a truncation has happened. The
Received
Length
is now130
andCurrent
Length
is128
. Warnings are typically routed here to the Simulink Diagnostic Viewer (see Systematic Diagnosis of Errors and Warnings (Simulink)).
Modify Maximum Size of a Variable-length Array
Change the maximum size of a variable-length array in Simulink. The default maximum of the Position
array in the sensor_msgs/JointState
message type is 128
. You will change this limit to 256
.
Open the example model, and double-click on the Work with Variable-length Arrays subsystem.
From the Simulation tab, select ROS Toolbox > Variable Size Messages.
From the list box on the left, click on
sensor_msgs/JointState
. Then, unselect the Use default limits for this message type checkbox. Finally, enter the new value (256
) in the row for the position
array property, and click OK to close the dialog.Click Play to start simulation.
Run the following at the MATLAB command line. Observe that a warning is not emitted in the Diagnostic Viewer.
msg.position = 1:200; % array of length 200
send(pub, msg);
Run the following at the MATLAB command line. Observe that a warning is emitted in the Diagnostic Viewer.
msg.position = 1:300; % array of length 300
send(pub, msg);
Close the model without saving.
Note:
The maximum size information applies to all instances of the
sensor_msgs/JointState
message type. For example, if other messages used in the model include asensor_msgs/JointState
message, the updated limit of256
will apply to all those nested instances as well.The maximum size information is specific to the model, and is saved with the model. You can have two models open that use
sensor_msgs/JointState
, with one model using the default limit of128
, and another using a custom limit of256
.
Work with Messages Using MATLAB Function Block
The Bus Assignment block in Simulink does not support assigning to an element inside an array of buses.
For example, a geometry_msgs/PoseArray
message has a Poses
property, which is required to be an array of geometry_msgs/Pose
messages. If you want to assign to specific elements of the Poses
array, that is not possible with the Bus Assignment block.
Explore how to use the MATLAB Function block for advanced message manipulation such as assignment of nested messages.
Open the example model. Select the Work with Nested Arrays of Messages subsystem and copy.
Open a new Simulink model. Paste and save the new model to a temporary location, with the name
FunctionTest.slx
.Close all models, and clear the base workspace by typing
clear
in the MATLAB command line.
Configure the MATLAB Assign Block
Open the FunctionTest.slx model, double-click on the Work with Nested Arrays of Messages subsystem, and open the MATLAB Function - Assign block. Observe that it uses MATLAB notation to assign values inside a nested array.
The Function Block requires the datatype of bus outputs (in this case,
msg
) to be explicitly specified. Create all buses required for this model by typing the following at the MATLAB command line. Note that the bus objects are created using the nameSL_Bus_<messageType>
and stored in the Simulink data dictionaryros2lib
. You can find this data dictionary under External Data > From Libraries in Model Explorer.
ros.ros2.createSimulinkBus(gcs)
Double-click the MATLAB Function - Assign block. Double-click the MATLAB Function - Assign block. In the MATLAB Editor toolstrip, under Modeling tab, click Symbols Pane. Then right click on
msg
, select Inspect and set its type toSL_Bus_geometry_msgs_PoseArray
.If you do not see
SL_Bus_geometry_msgs_PoseArray
listed as an option in the Type dropdown, select Refresh data types.If you are using variable-size messages within MATLAB Function block, you must enable Dynamic memory allocation in MATLAB functions setting under Model Settings > Simulation Target > Advanced parameters. You can open the advanced parameters by hovering over the two dots (..) at the bottom of the Simulation Target dialog.
Run Simulation
Under the Simulation tab, set Stop Time to
1.0
, and click Play to run the simulation. Verify that the values in the Display blocks are equal topi/2
andpi/2 + 1
.The
ros.ros2.createSimulinkBus(gcs)
statement has to be re-run each time the model is loaded. To avoid these issues, include this statement in theInitFcn
callback for the model (see Model Callback Parameters (Simulink)).
Work with String Arrays
A string array in a ROS message is represented in Simulink as an array of std_msgs/String
messages. Each std_msgs/String
message has a data
property that has the actual characters in the string. Each string is represented as an array of uint8
values.
By default, the maximum number of std_msgs/String
messages in a string array is 16
, and the maximum length of an individual string is 128
characters. The following steps show how to change these defaults:
Open the example model, and double-click the Work with Strings and String Arrays subsystem.
Change Maximum Array Lengths
From the Simulation tab, select ROS Toolbox > Variable Size Messages.
In the Message types in model column, click on the
sensor_msgs/JointState
entry. Observe that the right-hand pane shows aName
property that is an array ofstd_msgs/String
, with a maximum length of16
. To change the maximum number of strings inName
, deselect the Use default limits for this message type checkbox and enter the desired value.
In the Message types in model column, click on the
std_msgs/String
entry. Observe that the right-hand pane shows a data
property that is an array ofuint8
, with a maximum length of128
. To change the maximum length of the string, deselect the Use default limits for this message type checkbox and enter the desired value.Once you change the default values, open the Work with Strings and String Arrays subsystem and simulate the model. The Display blocks should now reflect the updated maximum values.
Note: The maximum length of data
applies to all instances of std_msgs/String
in the model. For example, the Blank String block in Work with Strings and String Arrays subsystem uses a std_msgs/String
message, so these messages would inherit the updated maximum length. Likewise, if the model has another ROS message type with a string array property, the individual strings in that array will also inherit the updated maximum length.