Publishers and Subscribers

Introduction

This tutorial explains the basics of ROS2 Publisher and Subscriber.

  • Lines beginning with $ are terminal commands.

    • To open a new terminal → use the shortcut Ctrl + Alt + T.

    • To open a new tab inside an existing terminal → use the shortcut Ctrl + Shift +T.

    • To kill a process in a terminal → use the shortcut Ctrl + C.

  • Lines beginning with # indicate the syntax of the commands.

  • Code is separated in boxes.

  • Code is case sensitive.

Simple Publisher in ROS2

Given below is an example of a ROS node, including a publisher. The code is based on the simple structure of the node example of Day 2. It is the simplest way of programming a ROS2 node including the typical ROS2 communication. Feel free to adjust the code structure in your later projects based on your programming skills. Go through the explanation before you start with the exercise.

Listing 9 Example 1. simple ROS2 publisher node.
#!/usr/bin/env python3

import rclpy
from std_msgs.msg import String

def main():
    global mypub
    rclpy.init()
    myfirstpublisher = rclpy.create_node('myfirstpublisher')
    mypub = myfirstpublisher.create_publisher(String, 'myfirsttopic', 1)
    myfirstpublisher.create_timer(0.1, mytimercallback)
    try:
        rclpy.spin(myfirstpublisher)
    except KeyboardInterrupt:
        pass

    myfirstpublisher.destroy_node()
    rclpy.shutdown()

def mytimercallback():
    global mypub
    mymsg = String()
    mymsg.data = 'Hello ROS2 Communication'
    mypub.publish(mymsg)

if __name__ == '__main__':
    main()

Publisher explanation

The following lines explain the given code structure. Do not enter them in the terminal!

from std_msgs.msg import String

Imports the ROS message String from the ROS package std_msgs (http://wiki.ros.org/std_msgs). Pay attention that this ROS message is not of the data type String! It is a message that includes a field of the data type String (see figure 1).

../../../_images/string_msg.png

Figure 5 Example 2. ROS String message

    mypub = myfirstpublisher.create_publisher(String, 'myfirsttopic', 1)

This will initialize a publisher within the Node.

The first argument passed defines the Message type of the node. In this case it is a ROS String Message.

The second argument is the Topic name that the publisher will use to publish the Message. In this case the topic name is myfirsttopic.

The third argument passed it the queue_size, which is 1 in this example. Queue size is a required QoS (quality of service) setting that limits the amount of queued messages if a subscriber is not receiving them fast enough.

    myfirstpublisher.create_timer(0.1, mytimercallback)

This line declares a timer with a callback function to execute every 0.1 seconds. The function is named mytimercallback in this example.

        rclpy.spin(myfirstpublisher)

The `rlcpy.spin()` is already known, but it is worth to mention again that this line will check, if there is anything to to for the Node. In this example the Node has to execute the function mytimercallback every 0.1 seconds. In this function the publishing will take place, let’s have a look into it:

def mytimercallback():

This line just defines the function, its name and passed arguments.

    global mypub

The keyword global can be used in Python to manipulate variables with a global scope. If we were not using mypub globally, the function would create a new local variable mypub, which is only known inside the function. But mypub should be the publisher, which is part of the node and publish to the ROS2 world. That is the reason why have to make it globally available in the main() function as well.

To avoid this, we will need to use classes in Python, which we will see in the next example.

    mymsg = String()

This will instantiate an empty ROS message of the type String. For further information on ROS message initialization, check (http://wiki.ros.org/rospy/Overview/Messages).

    mymsg.data = 'Hello ROS2 Communication'

This is a direct field assignment to the field data of the initialized ROS message mymsg.

    mypub.publish(mymsg)

To publish the filled ROS message call publish() on the handle mypub and pass the message mymsg as argument.

Publisher Exercise:

Write your own ROS2 publisher:

Create a package named pubsub in your workspace robot_ws. Create a python file and name it publisher.py. Copy the given example to create your first own publisher in a ROS2 node.

Run the ROS2 node after adding an entry point to the setup.py file and building the package:

# ros2 run <package_name> <node_name>

Display active ROS nodes:

$ ros2 node list

Display published ROS messages:

$ ros2 topic echo /myfirsttopic

# ros2 topic echo <topic_name>

The following example code shows an alternative way with classes, avoiding global variables. You can chose, which version you prefer:

#!/usr/bin/env python3

import rclpy
from rclpy.node import Node
from std_msgs.msg import String

class MyPublisherClass(Node):

    def __init__(self):
        super().__init__('myfirstpublisher')
        self.mypub = self.create_publisher(String, 'myfirsttopic', 1)
        self.create_timer(0.1, self.mytimercallback)

    def mytimercallback(self):
        mymsg = String()
        mymsg.data = 'Hello ROS2 Communication'
        self.mypub.publish(mymsg)

def main():
    rclpy.init()
    myfirstpublisher = MyPublisherClass()
    try:
        rclpy.spin(myfirstpublisher)
    except KeyboardInterrupt:
        pass
    myfirstpublisher.destroy_node()
    rclpy.shutdown()

if __name__ == '__main__':
    main()

Simple Subscriber in ROS

Given below is an example of a ROS2 node, including a subscriber. The code is based on the simple structure of the node example of Day 2. It is the simplest way of programming a ROS node including the typical ROS communication. Feel free to adjust the code structure in your later projects. Go through the explanation before you start with the exercise.

Listing 10 Example 3. simple ROS subscriber node.
#!/usr/bin/env python3

import rclpy
from std_msgs.msg import String

def main():
    rclpy.init()
    myfirstsubscriber = rclpy.create_node('myfirstsubscriber')
    myfirstsubscriber.create_subscription(String, 'myfirsttopic', mysubcallback, 10)
    try:
        rclpy.spin(myfirstsubscriber)
    except KeyboardInterrupt:
        pass
    myfirstsubscriber.destroy_node()
    rclpy.shutdown()

def mysubcallback(msg):
    print('You said: ', msg.data)

if __name__ == '__main__':
    main()

Subscriber explanation

The following lines are only explanations of the given code structure. You don’t have to enter them in the terminal!

    myfirstsubscriber.create_subscription(String, 'myfirsttopic', mysubcallback, 10)
    try:

This declares a subscriber within the node.

The first argument passed defines the Message type of the node. In this case it is a ROS String Message.

The second argument is the Topic name that the subscriber will use to subscribe to messages. Message type and Topic name of publisher and subscriber must match to allow them to communicate. In this case the topic name is myfirsttopic.

The third argument passed is a callback function, which will be executed, when a new Message from the dedicated Topic appears. For this reason it is not necessary to define a timer for the subscriber. The timing is determined by the publisher.

The fourth and last required argument is the Qos (Quality of Service) policy that will be used for this subscriber. It is compulsory to define this in a ROS2 Subscriber, however this will be explained at a later stage. For now always use the value 10 here.

def mysubcallback(msg):

Here is the definition of the function being called, when a new message for the defined subscriber appears. It will automatically have 1 argument that is passed, which is the message itself, in this example we call it msg.

    print('You said: ', msg.data)

In line 18 the variables of the message are being addressed msg.data. You can also assign it to a variable and you are free to chose, what’s going to happen with the data you subscribe to. You can extend the callback function on your demand.

Subscriber exercise:

Write your own ROS2 subscriber:

Create a python file and name it sub.py. Copy the given example to create your first own subscriber in a ROS2 node.

Run the ROS node:

# ros2 run <package_name> <node_name>

Hint

Don’t forget that the publisher node must run to receive messages!

The following example code shows an alternative way with classes. You can chose, which version you prefer:

#!/usr/bin/env python3

import rclpy
from rclpy.node import Node
from std_msgs.msg import String

class MySubscriberClass(Node):

    def __init__(self):
        super().__init__('myfirstsubscriber')
        self.subscription = self.create_subscription(
            String, 'myfirsttopic', self.mysubcallback, 10)

    def mysubcallback(self, msg):
        print('You said: ', msg.data)

def main():
    rclpy.init()
    myfirstsubscriber = MySubscriberClass()
    try:
        rclpy.spin(myfirstsubscriber)
    except KeyboardInterrupt:
        pass
    myfirstsubscriber.destroy_node()
    rclpy.shutdown()

if __name__ == '__main__':
    main()