• +4917626969472
  • info@ur-techpartner.de

ROS Basics (02/17) – Topic : Publisher

Robot Operating System(ROS1/ROS2) ROS Programming

ROS Basics – Topic: Publisher

In this blog we will learn how to publish a message on a topic. As we have described in ROS Terminologies blogs, a publisher is a node that publish a message into a topic, while a topic is a channel where other ROS nodes can either publish or read (subscribe) information.

Publishing to a Topic

Since we have already learn how to create package and how to execute several commands, therefore now we will directly start our current task. Side by side, I will continue explaining new things that we will encounter in our way of learning ROS Programming.

First we open a new terminal and create a new package named “ros_basics” in “src” folder of “catkin_ws” workspace.

Run following command in a terminal

roscore

Run following command in a new terminal

cd ~/catkin_ws/src

Then run following command

catkin_create_pkg ros_basics rospy std_msgs

(This will create a new package which has dependencies on “rospy” and “std_msgs”)

Run the command

touch ros_basics/src/topic_publisher.py

(This will create a new file named “topic_publisher.py” in “src” folder of “ros_basics” package)

Run the command

chmod +x ros_basics/src/topic_publisher.py

(This will assign the execution permission)

Run the command

gedit ros_basics/src/topic_publisher.py

(This will open the file “topic_publisher” to be modified, you can open this file in any other IDE as you like)

Wrtie following code into the file

#!/usr/bin/env python
import rospy
from std_msgs.msg import Int32

rospy.init_node('topic_publisher')
pub = rospy.Publisher('counter', Int32)
rate = rospy.Rate(2)

count = 0

while not rospy.is_shutdown():
                pub.publish(count)
                count += 1
                rate.sleep()

Save and close the file

The execution of all above commands are shown in figure below

The python program file will look like as shown below

Note: you should take care of indentation in the code. Because python follows indentation instead of brackets. For example, in above case, there is no brackets after “while” loop, instead the code lines (which should come within the loop) are indented to next tab.

Run the command to go back to “catkin_ws” directory

cd ..

Run the command

catkin_make

(This will compile the whole “src” directory of “catkin_ws” workspace)

Run the command

source devel/setup.bash

(This will ensure that latest changes are available)

Run topic publisher node

At this stage when our package “ros_basics” is already compiled. The python program file “topic_publisher” is ready to be executed. Now we will use “rosrun” command which is used to execute one node. In the python program file “topic_publisher”, there is a publisher node which will be initiated to publish the message on topic “counter”. Let’s first execute the command.

The structure of “rosrun” command is

rosrun [Package_Name] [File_Name]

Run the command in terminal

rosrun ros_basics topic_publisher.py

We can see the execution of above command in figure below. The publisher node has started publishing message on the topic “counter”.

However, we cannot see the published data. This is because the node is just publishing message. And there is no subscriber node which can read and display the message. In next blogs, we will also create subscriber node to receive and display this message. Nevertheless we have other ways to view the published message.

Let’s first check if there is addition of a new topic “counter” in topic lists

Open a new terminal and run the command

rostopic list

We can see in output that the topic “/counter” is also in list as show in figure below

We can get further information of the topic “counter”

Run the command in terminal

rostopic info /counter

You can see the type of the topic, also the list of Publishers and Subscribers associated with it. Here only one publisher node “topic_publisher” is associated with the topic “counter” and no subscriber node is linked.

We have another command “rostopic echo” which will display the message being published on the topic.

Run in the terminal

rostopic echo /counter

You can see in figure below that the message is started being displayed. It will continue displaying the message. You can press Ctrl + c to stop it.

Another thing that we may be interested to know is the information about std_msgs/Int32.

Run the command in terminal

rosmsg show std_msgs/Int32

We can see that the message “std_msgs/Int32” actually has one variable named “data” of type “int32”. It means whenever we will use “std_msgs/Int32” an Integer value will be published (or displayed).

You can further play with it. For example, you can check that which nodes are currently running.

Run the command

rosnode list

you will see that “topic_publisher” node is also listed in the running nodes list as shown in following output

/rosout
/topic_publisher

Explaining the Python Program File

Now we explain the python file “topic_publisher.py” line by line as follows

#!/usr/bin/env python

(As already explained in previous blog, it is the first line that is always included at the top of python file)

import rospy

(This line is to import python library called “rospy”

from std_msgs.msg import Int32

(This line means that we are going to use (import) a 32-bit integer, defined in the ROS standard message package named “std_msgs”. Since we are using message from other package, therefore we need to add dependency in package.xml file. However, since we already added dependency while creating the package “ros_basics” package. The dependency in package.xml file was added automatically. We will see  package.xml in later sections.)

rospy.init_node(‘topic_publisher’)

(This line initiate the node called “topic_publisher”

pub = rospy.Publisher(‘counter’, Int32)

(A variable “pub” is created to publish on the topic. The code line also gives the topic name “counter” and specify the type of message (Int32) that will be publish to the topic.

rate = rospy.Rate(2)

(It set the rate. For example, here the data will be publish 2 times per second)

count = 0

(This is a simple variable which is assigned the value 0)

while not rospy.is_shutdown():

pub.publish(count)

count += 1

rate.sleep()

(Now a continuous while loop will be run (Until Ctrl + c is pressed), pub variable of  type publisher will publish the value of variable “count” on the topic. The count variable will also be incremented 1 every time the loop will execute. The last line rate.sleep() is to ensure the frequency rate that we have already set)

Conclusion

As we already knew that we have created a python file “topic_publisher.py” in the package “ros_basics”. This file initiate a publisher node which publish the Integer type data on topic “counter”. Since the package is already compiled. Now it means that we can run this python file any time. This will perform the same task every time we run it.

For example, close all terminals

Open a terminal and run the command

roscore

Run in a new terminal

rosrun ros_basics topic_publisher.py

You will see that the publisher node is initiated as in figure below

Now run in a new terminal

rostopic echo /counter -n 5

The published message on the topic “counter” will be displayed as shown in figure below

In above command line -n 5 means that rostopic will print 5 messages.

Without -n 5, it will continue printing messages until Ctrl + c is pressed as we have seenbefore.

Congratulations! Now you are able to create a publisher node and to print the messages on a topic. In next blog we will learn how to create a subscriber node to receive the message through a specific topic.

No comments