ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
8

Unexpected delay in rospy subscriber

asked 2012-12-10 10:13:14 -0500

vpradeep gravatar image

updated 2012-12-10 10:45:42 -0500

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!

edit retag flag offensive close merge delete

Comments

I'd look at the queing behavior on the publisher.

tfoote gravatar image tfoote  ( 2012-12-10 10:32:21 -0500 )edit

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.

vpradeep gravatar image vpradeep  ( 2012-12-10 10:43:29 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
9

answered 2012-12-10 10:49:17 -0500

vpradeep gravatar image

I've been able to remove the unexpected delay by adding a buff_size option to my subscriber:

sub = rospy.Subscriber('chatter', Image, imageCb, queue_size=1, buff_size=2**24)

I'm not totally sure what the implications are of adding a buff_size option nor am I sure why solves the issue. Better solutions/explanations are always welcome!

edit flag offensive delete link more

Comments

1

Oh my God this worked! I spent days trying to figure this out (at first I thought rospy had a bug with queue_size).

I think what's happening is that the default buff_size is too small for images, and so rospy just decides to use default infinite queue_size (and setting it to 1 won't help).

basheersubei gravatar image basheersubei  ( 2014-12-13 01:03:51 -0500 )edit

Can someone check this? Is this a bug in rospy?

basheersubei gravatar image basheersubei  ( 2014-12-13 01:04:14 -0500 )edit

See this answer for a great explanation for this behavior. :)

Falko gravatar image Falko  ( 2017-05-30 04:01:56 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2012-12-10 10:13:14 -0500

Seen: 6,185 times

Last updated: Dec 10 '12