Part 1 Subscriber Node
The Code¶
Copy all the code below into your subscriber.py
file and (again) make sure you read the annotations to understand how it all works!
#!/usr/bin/env python3
# A simple ROS subscriber node in Python
import rospy # (1)!
from std_msgs.msg import String
class Subscriber(): # (2)!
def callback(self, topic_message): # (3)!
print(f"The '{self.node_name}' node obtained the following message: '{topic_message.data}'")
def __init__(self): # (4)!
self.node_name = "simple_subscriber"
topic_name = {BLANK}
rospy.init_node(self.node_name, anonymous=True)
self.sub = rospy.Subscriber(topic_name, String, self.callback)
rospy.loginfo(f"The '{self.node_name}' node is active...")
def main(self):
rospy.spin() # (5)!
if __name__ == '__main__': # (6)!
node = Subscriber()
node.main()
-
As with our publisher node, we need to import the
rospy
client library and theString
message type from thestd_msgs.msg
library in order to write a Python ROS Node and use the relevant ROS messages: -
This time, we create a Python Class called
Subscriber()
instead. -
When building a subscriber, we need a callback function. Within this function, we define what we want to do with the messages that we obtain from the topic we're listening (subscribing) to:
In this case, we simply want to print the
String
message to the terminal. -
Here we define the initialisation operations for the class:
- Here, we firstly initialise a rospy node with a custom name (in the same way as we initialised the publisher node earlier).
- Then, we create a
rospy.Subscriber
object, set this to listen to the topic that we want to receive messages from, specify the message type used by this topic, and then define the callback function to use to process the data whenever a message comes in. - Then, we send a message to the terminal to indicate that our node is running.
-
The
rospy.spin()
method simply makes sure that ourmain()
keeps running until the node is shut down externally (i.e. by a user enteringCtrl+C
). -
Finally, the code is executed by again performing a
__name__
check, creating an instance of theSubscriber()
class and calling themain()
method from that class.
Fill in the Blank!
Replace the {BLANK}
in the code above with the name of the topic that our publisher.py
node was set up to publish to!
Don't Forget the Shebang!¶
First, don't forget the shebang, it's very important!
A Simpler Approach¶
The above code uses a Python Class structure. This approach will be very useful when we start to do more complex things later in the course, but for this exercise you could also achieve the same using the following simplified approach:
#!/usr/bin/env python3
import rospy
from std_msgs.msg import String
node_name = "simple_subscriber"
topic_name = {BLANK}
def callback_function(topic_message):
print(f"The '{node_name}' node obtained the following message: '{topic_message.data}'")
rospy.init_node(node_name, anonymous=True)
sub = rospy.Subscriber(topic_name, String, callback_function)
rospy.loginfo(f"The '{node_name}' node is active...")
rospy.spin()