-
Notifications
You must be signed in to change notification settings - Fork 2
Part 1 Subscriber Node
Copy all of the code below into your subscriber.py
file. Then, review the explainer (below) to understand how this all works.
#!/usr/bin/env python
# A simple ROS subscriber node in Python
import rospy
from std_msgs.msg import String
class Subscriber:
def callback(self, data):
print("Subscriber obtained the following message: \"{}\"".format(data.data))
def __init__(self):
rospy.init_node('subscriber_node', anonymous=True)
self.sub = rospy.Subscriber("chatter", String, self.callback)
rospy.loginfo("subscriber node is active...")
def main_loop(self):
rospy.spin()
if __name__ == '__main__':
subscriber_instance = Subscriber()
subscriber_instance.main_loop()
First, don't forget the shebang!
#!/usr/bin/env python
As with our publisher node, we need to import the rospy
client library and the String
message type from the std_msgs.msg
library in order to write a Python ROS Node and use the relevant ROS messages:
import rospy
from std_msgs.msg import String
Next, we create a Subscriber
class:
class Subscriber:
Within our class, we firstly create a callback function, for the rospy.Subscriber
method to use later. Within this function, we define what we want to do with the messages that we obtain from the topic we are listening to:
def callback(self, data):
print("Subscriber obtained the following message: \"{}\"".format(data.data))
In this case, we simply want to format the String
message and print it out to the terminal.
Next, we define our initialisation operations for the class:
def __init__(self):
rospy.init_node('subscriber_node', anonymous=True)
self.sub = rospy.Subscriber("chatter", String, self.callback)
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 that this topic uses the String
message type, and then define the function which will be called when a message is received. The received message will automatically be set as the first input to this function, so we need to make sure that the self.callback
function is configured to accept the message (or "data") as its first input (after self
).
Then, we send a message to the terminal to indicate that our node is active:
rospy.loginfo("subscriber node is active...")
Then, we define the functionality of the main loop, which will run continuously until the node is shut down:
def main_loop(self):
rospy.spin()
rospy.spin()
simply keeps the node running until it is shutdown externally (i.e. by a user entering Ctrl + C
).
Finally, the code is executed by again performing the standard Python name check, creating an instance of the Subscriber
class and calling the main_loop()
class method:
if __name__ == '__main__':
subscriber_instance = Subscriber()
subscriber_instance.main_loop()
The above code uses a Python Class structure, which becomes quite useful when we start to do more complex things with Python and ROS. This example is very simple however, so the following simplified approach would also work here:
#!/usr/bin/env python
import rospy
from std_msgs.msg import String
def callback_function(data):
print("Subscriber obtained the following message: \"{}\"".format(data.data))
rospy.init_node('subscriber_node', anonymous=True)
sub = rospy.Subscriber("chatter", String, callback_function)
rospy.loginfo("subscriber node is active...")
rospy.spin()
ROS Training
UK-RAS Manufacturing Robotics Challenge 2021
Tom Howard & Alex Lucas | The University of Sheffield