MATLAB Examples

Exchange Data with ROS Publishers and Subscribers

Contents

Introduction

The primary mechanism for ROS nodes to exchange data is to send and receive 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 will use a publisher to send data to a topic. A node that wants to receive that information will use 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 allowed to be transmitted.

This publisher/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.
  • Publisher 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 the following image:

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

  • Wait until a new message is received, or
  • Use callbacks to process new messages in the background

Prerequisites: docid:robotics_examples.example-ROSGettingStartedExample, docid:robotics_examples.example-ROSNetworkingExample

Subscribe and Wait for Messages

  • Start the ROS master in MATLAB®, and create a sample ROS network with several publishers and subscribers.
rosinit
exampleHelperROSCreateSampleNetwork
Initializing ROS master on http://bat7842maci:64726/.
Initializing global node /matlab_global_node_00587 with NodeURI http://bat7842maci:64730/
  • Use rostopic list to see which topics are available. Assume you want to subscribe to the /scan topic.
rostopic list
/pose  
/rosout
/scan  
  • 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://bat7842maci:64748/)
 
Subscribers:
* /node_2 (http://bat7842maci:64742/)
* /node_1 (http://bat7842maci:64736/)
  • 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.
laser = rossubscriber('/scan')
laser = 

  Subscriber with properties:

        TopicName: '/scan'
      MessageType: 'sensor_msgs/LaserScan'
    LatestMessage: [0x1 LaserScan]
       BufferSize: 1
    NewMessageFcn: []

  • 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 = 

  ROS LaserScan message with properties:

       MessageType: 'sensor_msgs/LaserScan'
            Header: [1x1 Header]
          AngleMin: -0.5216
          AngleMax: 0.5243
    AngleIncrement: 0.0016
     TimeIncrement: 0
          ScanTime: 0.0330
          RangeMin: 0.4500
          RangeMax: 10
            Ranges: [640x1 single]
       Intensities: [0x1 single]

  Use showdetails to show the contents of the message

  • Some message types have convenient visualizers associated with them. For the LaserScan message, plot plots the scan data. The MaximumRange name-value pair specifies the maximum plot range.
figure
plot(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. One way of sharing data between your main workspace and the callback function is to use global variables. Also define two global variables pos and orient.
robotpose = rossubscriber('/pose',@exampleHelperROSPoseCallback)
global pos
global orient
robotpose = 

  Subscriber with properties:

        TopicName: '/pose'
      MessageType: 'geometry_msgs/Twist'
    LatestMessage: [1x1 Twist]
       BufferSize: 1
    NewMessageFcn: @exampleHelperROSPoseCallback

  • 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
orient
pos =

    0.0539   -0.0629   -0.0401


orient =

   -0.0260   -0.0078    0.1335

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 Callback Definition documentation for more information about defining callback functions.

Publish Messages

chatterpub = rospublisher('/chatter', 'std_msgs/String')
pause(2) % Wait to ensure publisher is registered
chatterpub = 

  Publisher with properties:

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

  • Create and populate a ROS message to send to the /chatter topic.
chattermsg = rosmessage(chatterpub);
chattermsg.Data = 'hello world'
chattermsg = 

  ROS String message with properties:

    MessageType: 'std_msgs/String'
           Data: 'hello world'

  Use showdetails to show the contents of the message

  • Use rostopic list to verify that the /chatter topic is available in the ROS network.
rostopic list
/chatter
/pose   
/rosout 
/scan   
  • 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)
chattersub = 

  Subscriber with properties:

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

  • Publish a message to the /chatter topic. Observe that the string is displayed by the subscriber callback.
send(chatterpub,chattermsg)
pause(2)
Chatter Callback message data: 

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. Also clear the global variables pos and orient
exampleHelperROSShutDownSampleNetwork
clear global pos orient
  • Shut down the ROS master and delete the global node.
rosshutdown
Shutting down global node /matlab_global_node_00587 with NodeURI http://bat7842maci:64730/
Shutting down ROS master on http://bat7842maci:64726/.

Next Steps