Note: This tutorial assumes that you have completed the previous tutorials: Writing a Simple Publisher and Subscriber (Python).
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Writing a Publisher and Subscriber with a Custom Message(Python)

Description: This tutorial covers how to write a publisher and subscriber using a custom message in python.

Keywords: custom message, publisher, subscriber, python

Tutorial Level: INTERMEDIATE

Writing the Custom Message

Before proceeding, a custom message should be defined following the Creating A Message tutorial.

The message used in this tutorial will be named Person.msg and have the following structure:

string name
int32 age

Writing the Publisher

Change directory the package that you wrote the custom message for. In this tutorial, the beginner_tutorials package will be used.

$ roscd beginner_tutorials

The Code

Inside the scripts folder of the beginner_tutorials package, lets create a file custom_talker.py:

   1 #!/usr/bin/env python
   2 import rospy
   3 from beginner_tutorials.msg import Person
   4 
   5 def talker():
   6     pub = rospy.Publisher('custom_chatter', Person)
   7     rospy.init_node('custom_talker', anonymous=True)
   8     r = rospy.Rate(10) #10hz
   9     msg = Person()
  10     msg.name = "ROS User"
  11     msg.age = 4
  12 
  13     while not rospy.is_shutdown():
  14         rospy.loginfo(msg)
  15         pub.publish(msg)
  16         r.sleep()
  17 
  18 if __name__ == '__main__':
  19     try:
  20         talker()
  21     except rospy.ROSInterruptException: pass

Don't forget to make the node executable:

$ chmod +x custom_talker.py

The Code Explained

Now, lets look at how this code differs from the code created in the simple publisher.

   3 from beginner_tutorials.msg import Person

If you recall, in the simple publisher, this line was:

   1 from std_msgs.msg import String

We have simply changed the package from std_msgs to beginner_tutorials and changed name of the message that's imported from String to Person

   6     pub = rospy.Publisher('custom_chatter', Person)

This line is very similar to the simple publisher version:

   1 pub = rospy.Publisher('chatter', String)

However, there are two changes.

First, we changed the name of the topic from chatter to custom_chatter. This change was made so we don't publish two different message types to the same topic.

Second, we changed the specified message type from String to our custom message Person.

   9     msg = Person()

This line assigns our variable to message object that we imported.

  10     msg.name = "ROS User"
  11     msg.age = 4

These lines change the attributes of our message. If we recall the format of our message:

string name
int32 age

It contains the name and the age field. These fields are now accessible as attributes to our message

Writing the Subscriber

The Code

Back in the scripts directory:

roscd beginner_tutorials/scripts

Lets create a file called custom_listener.py:

   1 #!/usr/bin/env python
   2 import rospy
   3 from beginner_tutorials.msg import Person
   4 
   5 def callback(data):
   6     rospy.loginfo("%s is age: %d" % (data.name, data.age))
   7 
   8 def listener():
   9     rospy.init_node('custom_listener', anonymous=True)
  10     rospy.Subscriber("custom_chatter", Person, callback)
  11 
  12     # spin() simply keeps python from exiting until this node is stopped
  13     rospy.spin()
  14 
  15 if __name__ == '__main__':
  16     listener()

Don't forget to make the node executable:

$ chmod +x custom_listener.py

The Code Explained

   3 from beginner_tutorials.msg import Person

Again, we need to import the message type so that we can use it.

   5 def callback(data):
   6     rospy.loginfo("%s is age: %d" % (data.name, data.age))

The message is given to this function by the variable that's passed in. In this case, data. As you can see in the loginfo() statement, we can access the attributes of the message as we would access the attributes of any type of object.

Building your nodes

Remember, in order for your messages to be generated, you must build your node.

Go to your catkin_workspace and run catkin_make:

$ cd ~/catkin_ws
$ catkin_make

Wiki: es/ROS/Tutoriales/CustomMessagePublisherSubscriber(python) (last edited 2021-02-16 17:00:02 by JuanEduardoRiva)