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

Publisher send rate drops with multiple clients in rospy

asked 2015-01-22 09:09:43 -0500

KareemShehata gravatar image

updated 2015-01-22 11:09:48 -0500

We noticed this as part of testing the Applanix Driver, which is written entirely in Python. On some machines, the send rate of the /applanix/nav message drops from the normal 100 Hz to 40 or even < 10 Hz as soon as there are subscribers listening and using the topic.

To test this out, I created the ros_py_tests [github] package. It's just a test harness with a rospy publisher set to publish Headers at 100 Hz, and rospy subscribers that listen check messages for time deltas and sequence numbers. I've copied the code below for reference, though do use the github version since I'll post updated code there.

# pub.py exerpt
pub = rospy.Publisher('test', Header, queue_size=10)
rospy.init_node('sender', anonymous=True)
rate = rospy.Rate(100)
msg = Header()
while not rospy.is_shutdown():
    msg.stamp = rospy.Time.now()
    msg.frame_id = "hello world %s" % msg.stamp
    pub.publish(msg)
    rate.sleep()

Here's the listener.

# sub.py excerpt
def callback(data):
    global last_seq
    # check that we haven't missed any messages
    if last_seq > 0 and data.seq != last_seq + 1:
        rospy.logerror("Sequence number mismatch: expected " + str(last_seq + 1)
            + " got " + data.seq)
    last_seq = data.seq

    # compare time stamps and print out
    rospy.loginfo("Received message with time " + format_time_str(data.stamp) + 
        ", delta " + format_time_str(rospy.Time.now() - data.stamp) + 
        ", message: " + str(data.frame_id))

rospy.init_node('listener', anonymous=True)
rospy.Subscriber("test", Header, callback)
rospy.spin()

There's a launch file included the package on GitHub that makes it really easy to start this test. Basic procedure:

  1. Start the publisher
  2. Start 5 of the listeners
  3. rostopic hz /test

Here's the strange part: it works perfectly well in virtual machines. On every Ubuntu host machine we've tried it on, the rate drops drastically once the listeners are running.

What's going on here? Why does having listeners kill the rate of sending of the publisher?

Update

I've added a cpp version of the publisher and the subscriber. Here's the result of testing the combinations:

           |    Subscriber   |
Publisher  | Python |   C++  |
Python     |  Fail  |  Fail  |
C++        |  Pass  |  Pass  |

Looks like it's pretty solidly something in the Python publisher, since the subscriber doesn't seem to matter.

edit retag flag offensive close merge delete

Comments

I've now created ros_comm issue #557 for this.

KareemShehata gravatar image KareemShehata  ( 2015-01-22 11:55:03 -0500 )edit

To anyone looking, it seems like this might be fixed in the latest version of rospy. If you can reproduce the problem on your machine, please try updating the ROS core packages.

KareemShehata gravatar image KareemShehata  ( 2015-01-23 07:19:35 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
1

answered 2015-01-23 16:09:34 -0500

KareemShehata gravatar image

Turns out this was a bug in rospy that has was fixed somewhere between rospy 1.10.2-0 and 1.10.11-0. We hadn't updated because of a package dependency problem. If you're seeing a problem like this in ROS hydro, make sure to update your packages, and do both an upgrade and a dist-upgrade!

edit flag offensive delete link more
1

answered 2015-01-22 15:21:59 -0500

gvdhoorn gravatar image

Could this be due to the use of synchronous publishing in rospy?

Looking at the code you posted, I don't see an explicit queue_size declared for your publisher. According to rospy/Overview/Publishers and Subscribers - queue_size: publish() behavior and queuing, the queue_size needs to be set for asynchronous publishing to work.

edit flag offensive delete link more

Comments

The queue_size is being set. It's on the first line of the excerpt from pub.py.

pub = rospy.Publisher('test', Header, queue_size=10)
KareemShehata gravatar image KareemShehata  ( 2015-01-22 15:56:32 -0500 )edit

Hm, must've been late last night when reading this. Seems you're right.

gvdhoorn gravatar image gvdhoorn  ( 2015-01-23 03:24:05 -0500 )edit

No worries. I had to check myself to make sure. :)

KareemShehata gravatar image KareemShehata  ( 2015-01-23 07:18:39 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-01-22 09:09:43 -0500

Seen: 449 times

Last updated: Jan 23 '15