rospy threading model
Is it correct to assume that a new thread will be used for every instance of every subscription and service callback?
ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
Is it correct to assume that a new thread will be used for every instance of every subscription and service callback?
For a particular topic, there is only one thread that all the subscribers share.
Each service callback does get its own thread because there can only be one service callback for a particular service.
Future versions of rospy will likely have a different, more versatile threading model for subscriptions.
The detailed replies have been great, but just to eliminate all ambiguity, from what I understand this also means that my script will wait for my callback to end before starting another callback, even if a subscription releases a new message. Is this correct?
The accepted answer is not correct, at least with Kinetic. Consider the following:
#!/usr/bin/env python
import threading
import rospy
from std_msgs.msg import Empty
global i
i = 0
def callback(_):
global i
i += 1
j = i
while not rospy.is_shutdown():
print('sleeping: %d, thread: %s' % (j, threading.current_thread()))
rospy.Rate(1).sleep()
print('exiting loop for %d: %s' % (j, rospy.is_shutdown()))
def main():
rospy.init_node('foooo')
sub = rospy.Subscriber('foo', Empty, callback, queue_size=1)
if __name__ == '__main__':
main()
rospy.spin()
Then, call rostopic twice by running the following command twice in parallel in different shell sessions:
rostopic pub /foo std_msgs/Empty "{}"
Observe the following output:
sleeping: 1, thread: <Thread(/foo, started daemon 140177158719232)>
sleeping: 2, thread: <Thread(/foo, started daemon 140177150326528)>
sleeping: 1, thread: <Thread(/foo, started daemon 140177158719232)>
sleeping: 2, thread: <Thread(/foo, started daemon 140177150326528)>
sleeping: 1, thread: <Thread(/foo, started daemon 140177158719232)>
sleeping: 2, thread: <Thread(/foo, started daemon 140177150326528)>
sleeping: 1, thread: <Thread(/foo, started daemon 140177158719232)>
sleeping: 2, thread: <Thread(/foo, started daemon 140177150326528)>
sleeping: 1, thread: <Thread(/foo, started daemon 140177158719232)>
sleeping: 2, thread: <Thread(/foo, started daemon 140177150326528)>
sleeping: 1, thread: <Thread(/foo, started daemon 140177158719232)>
sleeping: 2, thread: <Thread(/foo, started daemon 140177150326528)>
It actually seems like a subscriber process has one thread per topic subscribed per publisher. So if node A subscribes to topic /foo
and node B publishes to topic /foo
and node C also publishes to topic /foo
, node A will have 2 callback threads.
ros_thread_sub.py
#!/usr/bin/env python
import threading
import rospy
from std_msgs.msg import String
def callback(msg):
print("Msg from %s on thread %s" % (msg.data, threading.current_thread()))
def main():
rospy.init_node('foooo')
rospy.Subscriber('foo', String, callback, queue_size=1)
rospy.spin()
if __name__ == '__main__':
main()
ros_thread_pub.py (starting publisher B and C in separate terminals)
#!/usr/bin/env python
import threading
import sys
import rospy
from std_msgs.msg import String
global proc_id
proc_id = ""
def publisher():
msg = String(proc_id)
r = rospy.Rate(1)
pub = rospy.Publisher('foo', String, queue_size=1)
while not rospy.is_shutdown():
print("publishing")
pub.publish(msg)
r.sleep()
def main():
global proc_id
proc_id = sys.argv[1]
rospy.init_node(proc_id)
thread = threading.Thread(target=publisher)
thread.start()
rospy.spin()
if __name__ == '__main__':
main()
Console output:
Msg from B on thread <Thread(/foo, started daemon 140237958694656)>
Msg from B on thread <Thread(/foo, started daemon 140237958694656)>
Msg from B on thread <Thread(/foo, started daemon 140237958694656)>
Msg from B on thread <Thread(/foo, started daemon 140237958694656)>
Msg from C on thread <Thread(/foo, started daemon 140237950301952)>
Msg from B on thread <Thread(/foo, started daemon 140237958694656)>
Msg from C on thread <Thread(/foo, started daemon 140237950301952)>
Msg from B on thread <Thread(/foo, started daemon 140237958694656)>
Msg from C on thread <Thread(/foo, started daemon 140237950301952)>
Msg from B on thread <Thread(/foo, started daemon 140237958694656)>
Asked: 2011-03-23 09:06:32 -0600
Seen: 17,183 times
Last updated: Apr 18 '18