Main Content

Explore ROS Topics: Publisher and Subscriber Guide

Nodes use individual communication pipelines, known as topics, to communicate with other nodes. The data type used in topic communication is message. Topics are a key part of the ROS publish/subscribe communication model.

  • Publisher –– Publishers are nodes which produce data. Publisher nodes can publish a specific type of message over a topic and make it available for the subscriber nodes.

  • Subscriber –– Subscribers are nodes which consume data. Subscriber nodes can subscribe to messages or information published on a topic.

ROS Topics publish and subscribe mechanism diagram

Message Interface

Nodes exchange data units known as messages. These messages are described in .msg files and consists of two parts: fields and constants. The fields value represents the data sent within the message, while the constants value defines useful values for interpreting those fields.

ROS messages are structured data types and categorized into different types, based on their purpose. For example, a message designed to move a robot wheel differs from a message intended to capture an image from the robot's camera.

You can view the list of available message types by using rosmsg list.

rosmsg list
std_msgs/Bool                                                  
std_msgs/Byte                                                  
std_msgs/ByteMultiArray                                        
std_msgs/Char                                                  
std_msgs/ColorRGBA                                             
std_msgs/Duration                                              
std_msgs/Empty                                                 
std_msgs/Float32                                               
std_msgs/Float32MultiArray                                     
std_msgs/Float64                                               
std_msgs/Float64MultiArray                                     
std_msgs/Header                                                
std_msgs/Int16                                                 
std_msgs/Int16MultiArray                                       
std_msgs/Int32                                                 
std_msgs/Int32MultiArray                                       
std_msgs/Int64                                                 
std_msgs/Int64MultiArray                                       
std_msgs/Int8                                                  
std_msgs/Int8MultiArray                                        
std_msgs/MultiArrayDimension                                   
std_msgs/MultiArrayLayout                                      
std_msgs/String                                                
std_msgs/Time...

This list contains message types of predefined message interface definitions.

You can create a message of any of these predefined types such as example_interfaces/Int32.

firstMsg = rosmessage("std_msgs/Int32")
firstMsg = 

  ROS Int32 message with properties:

    MessageType: 'std_msgs/Int32'
           Data: 0

The firstMsg message contains various attached fields, one of which is the Data field. You can set the Data field to a supported value of your choice, which is the constant attached to it. The code below sets the Data field to a constant - integer value 5.

firstMsg.Data = int32(5)
firstMsg = 

  ROS Int32 message with properties:

    MessageType: 'std_msgs/Int32'
           Data: 5

You can also create messages with field set to different constants, with specific data types such as string, float, and bool as shown in these examples respectively.

secondMsg = rosmessage("std_msgs/String");
secondMsg.Data = "Hello World!"
secondMsg = 

  ROS String message with properties:

    MessageType: 'std_msgs/String'
           Data: 'Hello World!'
thirdMsg = rosmessage("std_msgs/Float32");
thirdMsg.Data = 10.05
thirdMsg = 

  ROS Float32 message with properties:

    MessageType: 'std_msgs/Float32'
           Data: 10.0500
fourthMsg = rosmessage("std_msgs/Bool");
fourthMsg.Data = true
ROS Bool message with properties:

    MessageType: 'std_msgs/Bool'
           Data: 1

For more information on various ways to create, inspect, and populate ROS 2 messages in MATLAB that are commonly encountered in robotics applications, see Work with Basic ROS Messages.

Publish Message to Topic and Subscribe to that Message

Exchange Data with ROS Publishers and Subscribers

This example shows how to publish and subscribe to topics in a ROS network.

The primary mechanism for ROS nodes to exchange data is sending and receiving messages. Messages are transmitted on a topic, and each topic has a unique name in the ROS network. If a node wants to share information, it uses a publisher to send data to a topic. A node that wants to receive that information uses a subscriber to that same topic. Besides its unique name, each topic also has a message type, which determines the types of messages that are capable of being transmitted under that topic.

This publisher and subscriber communication has the following characteristics:

  • Topics are used for many-to-many communication. Many publishers can send messages to the same topic and many subscribers can receive them.

  • Publishers and subscribers are decoupled through topics and can be created and destroyed in any order. A message can be published to a topic even if there are no active subscribers.

The concept of topics, publishers, and subscribers is illustrated in this figure.

Besides how to publish and subscribe to topics in a ROS network, this example also shows how to:

  • Wait until a new message is received

  • Use callbacks to process new messages in the background

Subscribe and Wait for Messages

Start the ROS master in MATLAB® using the rosinit command.

rosinit
Launching ROS Core...
...Done in 3.6961 seconds.
Initializing ROS master on http://172.19.136.75:56426.
Initializing global node /matlab_global_node_67357 with NodeURI http://vdi-wd1bgl-223:60706/ and MasterURI http://localhost:56426.

Create a sample ROS network with several publishers and subscribers using the provided helper function exampleHelperROSCreateSampleNetwork.

exampleHelperROSCreateSampleNetwork

Use rostopic list to see which topics are available.

rostopic list
/pose  
/rosout
/scan  
/tf    

Use rostopic info to check if any nodes are publishing to the /scan topic. The command below shows that node_3 is publishing to it.

rostopic info /scan
Type: sensor_msgs/LaserScan
 
Publishers:
* /node_3 (http://vdi-wd1bgl-223:60722/)
 
Subscribers:
* /node_1 (http://vdi-wd1bgl-223:60711/)
* /node_2 (http://vdi-wd1bgl-223:60717/)

Use rossubscriber to subscribe to the /scan topic. If the topic already exists in the ROS network (as is the case here), rossubscriber detects its message type automatically, so you do not need to specify it. Use messages in struct format for better efficiency.

laser = rossubscriber("/scan","DataFormat","struct");
pause(2)

Use receive to wait for a new message. (The second argument is a time-out in seconds.) The output scandata contains the received message data.

scandata = receive(laser,10)
scandata = struct with fields:
       MessageType: 'sensor_msgs/LaserScan'
            Header: [1×1 struct]
          AngleMin: -0.5467
          AngleMax: 0.5467
    AngleIncrement: 0.0017
     TimeIncrement: 0
          ScanTime: 0.0330
          RangeMin: 0.4500
          RangeMax: 10
            Ranges: [640×1 single]
       Intensities: []

Some message types have visualizers associated with them. For the LaserScan message, rosPlot plots the scan data. The MaximumRange name-value pair specifies the maximum plot range.

figure
rosPlot(scandata,"MaximumRange",7)

Subscribe Using Callback Functions

Instead of using receive to get data, you can specify a function to be called when a new message is received. This allows other MATLAB code to execute while the subscriber is waiting for new messages. Callbacks are essential if you want to use multiple subscribers.

Subscribe to the /pose topic, using the callback function exampleHelperROSPoseCallback.

robotpose = rossubscriber("/pose",@exampleHelperROSPoseCallback,"DataFormat","struct")
robotpose = 
  Subscriber with properties:

                      TopicName: '/pose'
                  LatestMessage: []
                    MessageType: 'geometry_msgs/Twist'
                     BufferSize: 1
    MessagePreprocessingEnabled: 0
                  NewMessageFcn: @exampleHelperROSPoseCallback
                     DataFormat: 'struct'

One way of sharing data between your main workspace and the callback function is to use global variables. Define two global variables pos and orient.

global pos
global orient

The global variables pos and orient are assigned in the exampleHelperROSPoseCallback function when new message data is received on the /pose topic.

Wait for a few seconds to make sure that the subscriber can receive messages. The most current position and orientation data will always be stored in the pos and orient variables.

pause(2) 
pos
pos = 1×3

    0.0429    0.0230   -0.0011

orient
orient = 1×3

    0.0079   -0.0263   -0.0041

If you type in pos and orient a few times in the command line, you can see that the values are continuously updated.

Stop the pose subscriber by clearing the subscriber variable

clear robotpose

Note: There are other ways to extract information from callback functions besides using globals. For example, you can pass a handle object as additional argument to the callback function. See the Create Callbacks for Graphics Objects documentation for more information about defining callback functions.

Publish Messages

Create a publisher that sends ROS string messages to the /chatter topic (see Work with Basic ROS Messages).

chatterpub = rospublisher("/chatter","std_msgs/String","DataFormat","struct")
chatterpub = 
  Publisher with properties:

         TopicName: '/chatter'
    NumSubscribers: 0
        IsLatching: 1
       MessageType: 'std_msgs/String'
        DataFormat: 'struct'

pause(2) % Wait to ensure publisher is registered

Create and populate a ROS message to send to the /chatter topic.

chattermsg = rosmessage(chatterpub);
chattermsg.Data = 'hello world'
chattermsg = struct with fields:
    MessageType: 'std_msgs/String'
           Data: 'hello world'

Use rostopic list to verify that the /chatter topic is available in the ROS network.

rostopic list
/chatter
/pose   
/rosout 
/scan   
/tf     

Define a subscriber for the /chatter topic. exampleHelperROSChatterCallback is called when a new message is received and displays the string content in the message.

chattersub = rossubscriber("/chatter",@exampleHelperROSChatterCallback,"DataFormat","struct")
chattersub = 
  Subscriber with properties:

                      TopicName: '/chatter'
                  LatestMessage: []
                    MessageType: 'std_msgs/String'
                     BufferSize: 1
    MessagePreprocessingEnabled: 0
                  NewMessageFcn: @exampleHelperROSChatterCallback
                     DataFormat: 'struct'

Publish a message to the /chatter topic. The string is displayed by the subscriber callback.

send(chatterpub,chattermsg)
pause(2)
ans = 
'hello world'

The exampleHelperROSChatterCallback function was called as soon as you published the string message.

Shut Down ROS Network

Remove the sample nodes, publishers, and subscribers from the ROS network. Clear the global variables pos and orient.

exampleHelperROSShutDownSampleNetwork
clear global pos orient

Shut down the ROS master and delete the global node.

rosshutdown;

Custom Message Support for ROS Topics

Utilizing predefined interface definitions is generally considered a best practice. However, there are situations where the standard message types may not align with the specific requirements of your robotic application. For instance, if you require a message format for managing inventory that includes fields for item name, quantity, and storage location, you need to create custom ROS messages. ROS Toolbox supports ROS custom message generation which is elaborated in ROS Custom Message Support.

You can generate ROS custom messages by reading ROS custom message definitions in the specified folder path by using rosgenmsg. The function folder must contain one or more ROS packages. These packages contain the message definitions in .msg files. You can also create a shareable ZIP archive of the generated custom messages and use this ZIP archive to register the custom messages in another machine by using rosRegisterMessages.

In MATLAB®, you typically don't write .msg files directly. Instead, you create custom messages using ROS package tools and then use them in MATLAB.

See Also

| |

Related Topics

External Websites