Main Content

Update Header Field of a ROS Message in Simulink®

This example illustrates how to update the header field of a ROS message using Simulink®.

Some ROS messages contain a specific Header field which maps to std_msgs/Header message type. The Header field contains the timestamp and coordinate frame information of the ROS message. This example model shows how to use the Header Assignment Block to update that information for a ROS message, in Simulink®.

open_system('rosHeaderAssignmentBlockExampleModel.slx')

The Blank Message block creates an empty ROS message of type, sensor_msgs/LaserScan. Any other message type that contains a Header field of type std_msgs/Header can be used here, instead. The output of the Blank Message block is then fed to the Header Assignment block, which updates the Header field of this message. For display, the frame_id and stamp values of the updated ROS message Header are selected from the list of bus elements using Bus Selector blocks. Additionally, a blank /rosgraph_msgs/Clock message is created and a custom time based on the current simulation time is published to the /clock topic on the ROS network.

fullblock2.png

Update coordinate frame id and timestamp values in the Header

Open the Header Assignment block to display its block parameters. The Set Frame ID option is selected and the name of the coordinate frame that is associated with the message is specified in the text box as lidar_link. This will be set as the frame_id value for the Header. The Set Timestamp option is also selected which sets the stamp value of the Header to the current ROS System time, by default. The Header field name option is set to Use the default Header field name because, the name of the Header field in a blank message is its default value, header. If you are using a ROS message with a custom name for the Header field, you can select the Specify your own option from the dropdown and specify the name of the Header field in the text box.

Before running the model, call rosinit to connect to a ROS network.

rosinit
Launching ROS Core...
Done in 0.65247 seconds.
Initializing ROS master on http://172.29.218.114:49381.
Initializing global node /matlab_global_node_27470 with NodeURI http://dcc898908glnxa64:45715/ and MasterURI http://localhost:49381.

Run the model. You can see the updated values for the frame_id and stamp fields of the ROS Message in their respective displays.

sim('rosHeaderAssignmentBlockExampleModel')

ex1.png

Update timestamp value in the Header based on a custom clock

In some cases it is useful to set the timestamp of a ROS message based on the time published by a clock server than the ROS System time. A clock server is a specialized ROS node that publishes timestamp to /clock topic in the form of rosgraph_msgs/Clock message type. In order to enable this behavior for the Header Assignment block, set the /use_sim_time ROS parameter to true.

rosparam set /use_sim_time true

This configures the Header Assignment block to look for /clock topic on the ROS Network and update the timestamp of the ROS Message accordingly. If /clock topic is not being published, the timestamp will be zeros. Since the Header Assignment block updates during every sample hit, the accuracy of the timestamp always depends on the step-size of the solver. Smaller step-size values result in more accurate timestamp values. Run the model. You should see the time in stamp field of the ROS message based on the published /clock topic, not the current ROS System Time.

sim('rosHeaderAssignmentBlockExampleModel')

ex2.png

Shut down the ROS network.

rosshutdown
Shutting down global node /matlab_global_node_27470 with NodeURI http://dcc898908glnxa64:45715/ and MasterURI http://localhost:49381.
Shutting down ROS master on http://172.29.218.114:49381.