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

With rospy, messages don't seem to be recieved if published soon after creating the publisher

asked 2012-04-29 17:33:22 -0500

Murph gravatar image

I've got an app like this:

#!/usr/bin/env python
PKG_NAME = 'straight'
import roslib; roslib.load_manifest(PKG_NAME)
import rospy
from std_msgs.msg import String

if __name__ == '__main__':
    rospy.init_node("test")
    speakPub = rospy.Publisher('/testing', String)
    speakPub.publish(String("Hello World"))

And that message never seems to get received anywhere (my other node listening for it, or the rostopic echo i have running on another terminal). However, if I add rospy.sleep(1) between creating the publisher and using it, then the message gets through.

Am I doing something wrong? Do I need to wait between creating the publisher and using it?

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
5

answered 2012-04-29 17:41:04 -0500

Eric Perko gravatar image

This is normal (also... I assume you have a rospy.spin() after you publish, or else things are getting destructed too early). See http://answers.ros.org/question/9665/test-for-when-a-rospy-publisher-become-available?answer=14125#post-id-14125

Basically, there is a nonzero amount of time where a subscriber actually subscribes to a publisher. If a publisher publishes a message during that time, the subscriber will not receive it, as it was not yet subscribed when the message was sent. If you want any subscriber to get the last message the publisher sent when it connects, you should use a latched topic.

When you do rospy.sleep(1) before publishing, you are allowing some time for the subscribers to connect before you actually publish the message. Therefore, the subscriber does receive the message.

edit flag offensive delete link more
0

answered 2017-01-20 05:21:21 -0500

junya gravatar image

I could overcome this behavior by comparing number of subscribers and number of connections in publisher.

# -*- coding: utf-8 -*-
import time

import rosgraph
import rospy
from std_msgs.msg import String


def get_publisher(topic_path, msg_type, **kwargs):
    pub = rospy.Publisher(topic_path, msg_type, **kwargs)
    num_subs = len(_get_subscribers(topic_path))

    for i in range(10):
        num_cons = pub.get_num_connections()
        if num_cons == num_subs:
            break
        time.sleep(0.1)
    else:
        raise RuntimeError("mismatch !!")

    return pub


def _get_subscribers(topic_path):
    u""" topic_path を subscribe している subscriber のノード名を取得する """
    # rostopic の実装を参考に実装
    topic_path = rosgraph.names.script_resolve_name('rostopic', topic_path)
    ros_master = rosgraph.Master('/rostopic')
    state = ros_master.getSystemState()
    subs = []
    for sub in state[1]:
        if sub[0] == topic_path:
            subs.extend(sub[1])
    return subs


if __name__ == "__main__":
    rospy.init_node("test")
    pub = get_publisher('/testing', String, queue_size=1)
    pub.publish(String("Hello World"))
edit flag offensive delete link more

Question Tools

Stats

Asked: 2012-04-29 17:33:22 -0500

Seen: 3,595 times

Last updated: Jan 20 '17