Unexpected delay in rospy subscriber
I'm trying to do some image processing in a python subscriber callback, and I'm seeing some unexpected latency in the system. It seems that even though I subscribe to a topic with queue_size=1
, I still receive old messages. Also, when I remove the sleep(1.0)
call from my listener callback, I get Delay: 0.019
, which is the expected result.
See code snippets below:
talker.py
#!/usr/bin/env python
import roslib; roslib.load_manifest('sensor_msgs')
import rospy
from sensor_msgs.msg import Image
rospy.init_node('talker')
pub = rospy.Publisher('chatter', Image)
while not rospy.is_shutdown():
msg = Image()
msg.data = [0]*(640*480)
msg.header.stamp = rospy.Time.now()
pub.publish(msg)
rospy.sleep(0.05)
listener.py
#!/usr/bin/env python
import roslib; roslib.load_manifest('sensor_msgs')
import rospy
from sensor_msgs.msg import Image
def imageCb(msg):
print "Delay:%6.3f" % (rospy.Time.now() - msg.header.stamp).to_sec()
rospy.sleep(1.0)
rospy.init_node('listener')
sub = rospy.Subscriber('chatter', Image, imageCb, queue_size=1)
rospy.spin()
When I run both nodes, listener.py outputs the following:
Delay: 0.023
Delay: 0.950
Delay: 1.879
Delay: 1.950
Delay: 2.876
Delay: 3.805
Delay: 4.733
Delay: 5.657
Delay: 5.954
Delay: 5.954
Delay: 6.882
Delay: 6.916
Delay: 6.917
Delay: 6.918
Delay: 6.916
Delay: 6.917
Is this a bug in rospy? Or, maybe there's some other Subscriber option that I should be using?
This is on Lucid/Fuerte system.
Thanks!
I'd look at the queing behavior on the publisher.
I know roscpp publishers have a configurable queue_size. Do python publishers have a similar option? Also, I've seen the above issue also occur with a roscpp publisher with a queue_size=1. This suggests that the rospy subscriber is causing the problem.