Parking Lot

ROS callbacks and threading

It is important to develop an accurate mental model of how your Python code is executed by the ROS runtime. To explore this, first run through the ROS tutorials on creating your first Python publisher and subscriber.

You will notice that as ROS is event-driven, you never have to explicitly invoke your subscriber call back in the listener module. In the case where your code is processing messages as fast as they are arriving from the talker, it is easy to think of the flow of execution being something like this:

talker generates message
listener receives message and prints the contents to the console
talker generates message
listener receives message and prints the contents to the console
talker generates message
...

There will be times when you will want to execute code in response to a ROS message that takes longer to run than the time between message arrivals. In this case, it is important to understand what is happening under the hood.

Modify listener.py script by inserting a sleep inside the subscriber callback

#!/usr/bin/env python
import rospy
from std_msgs.msg import String
import time
def callback(data):
    rospy.loginfo(rospy.get_caller_id() + "I heard %s", data.data)
    time.sleep(10)
def listener():
    # In ROS, nodes are uniquely named. If two nodes with the same
    # node are launched, the previous one is kicked off. The
    # anonymous=True flag means that rospy will choose a unique
    # name for our 'listener' node so that multiple listeners can
    # run simultaneously.
    rospy.init_node('listener', anonymous=True)
    rospy.Subscriber("chatter", String, callback)
    # spin() simply keeps python from exiting until this node is stopped
    rospy.spin()
if __name__ == '__main__':
    listener()

What happens when you run this code? What assumption can you safely make about any code that you put in a sensor callback? In what ways might the behavior you observe be suboptimal when programming a robot? Add your answers to writeup.txt.

Modify listener.py again to explicitly specify a queue_size for your subscriber.

#!/usr/bin/env python
import rospy
from std_msgs.msg import String
import time
def callback(data):
    rospy.loginfo(rospy.get_caller_id() + "I heard %s", data.data)
    time.sleep(10)
def listener():
    # In ROS, nodes are uniquely named. If two nodes with the same
    # node are launched, the previous one is kicked off. The
    # anonymous=True flag means that rospy will choose a unique
    # name for our 'listener' node so that multiple listeners can
    # run simultaneously.
    rospy.init_node('listener', anonymous=True)
    rospy.Subscriber("chatter", String, callback, queue_size=1)
    # spin() simply keeps python from exiting until this node is stopped
    rospy.spin()
if __name__ == '__main__':
    listener()

What happens now? In what scenarios is this behavior good? In what scenarios is this behavior bad? Add your responses to writeup.txt.