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

Cleanly exit from python publisher ensuring all messages sent

asked 2014-07-03 12:48:32 -0500

micah.corah gravatar image

updated 2014-07-03 14:31:38 -0500

I have been working on a Python node that essentially publishes one-off messages and then exits. Due, I believe, to the threading in rospy, messages are not always sent if the script exits soon after publishing a message. I have also found no ways of truly guaranteeing that messages that sent messages are received.

Here is some example code based roughly on the nodes demonstrated in the ROS tutorials:

Publisher

#!/usr/bin/python

from std_msgs.msg import Header
import rospy
import math

topic = 'foo'

publisher = rospy.Publisher(topic, Header, queue_size = 10)

rospy.init_node('publisher',anonymous = True)

msg = Header()
msg.frame_id = "Hello World!"
publisher.publish(msg)

Subscriber:

#!/usr/bin/python
import rospy
from std_msgs.msg import Header

def callback(data):
    rospy.loginfo(rospy.get_caller_id()+"I heard %s",data.frame_id)

def listener():
    rospy.init_node('listener', anonymous=True)

    rospy.Subscriber("foo", Header, callback)

    rospy.spin()

if __name__ == '__main__':
    listener()

There are a number of modifications I have found that will get the messages to send:

  1. Use a rospy.Rate object with sufficiently low rate and sleep after publishing
  2. Sending messages in a loop with no other calls to ROS functionality will result in most messages being received.
  3. edit I tried a loop while not rorpy.is_shutdown() containing rospy.signal_shutdown('stuff') after the message is sent. This method results in the message being received some of the time.

There are also some exceptions where the message may otherwise be expected to be received:

  1. Sleeping using a rospy.Duration object will not allow sends to complete
  2. rospy.signal_shutdown does not guarantee that pending messages are sent
  3. Pending sends are not completed when using a Rate object with too high a rate

On top of all this, I have found that rostopic echo will often (but not always) get messages when a subscribing node does not.

I would like to know if there is any (hopefully documented) way that I can exit a python script with the guarantee that every subscriber to a topic that node publishes will have received every message that has been published. So far I have not been able to find anything to this effect.

edit retag flag offensive close merge delete

3 Answers

Sort by ยป oldest newest most voted
3

answered 2014-07-03 13:22:04 -0500

If you want to make sure a message was sent, the simplest solution is to check that it was received. Have your node subscribe to the topic you're publishing on, and exit when it receives a message. However, topics in ROS aren't really designed to be used this way. If you want to be really sure your message has been received, this is what services are for.

Alternatively, depending on the data type, your node could set a parameter with its data on the parameter server rather than publishing. This data would then be available for any node that wanted it even after the publishing node shuts down.

edit flag offensive delete link more

Comments

Adding on what @dan-lazewatsky said, many people have had problems creating a publisher, and then immediately publishing. If you only want to publish once, and then exit, you might want to also consider adding a delay between publisher creation and message publishing.

jarvisschultz gravatar image jarvisschultz  ( 2014-07-03 13:33:30 -0500 )edit

What I have been seeing is that some subscribers will get a message but not others so self-subscribing provides no guarantee (i.e. "rostopic echo" may get messages when another node doesn't) Good point about services, I was planning the switch. A delay may fix that problem, but it would be a hack.

micah.corah gravatar image micah.corah  ( 2014-07-03 14:12:14 -0500 )edit
2

answered 2014-07-09 11:28:02 -0500

micah.corah gravatar image

updated 2014-07-09 11:34:25 -0500

Answering my own question:

I found my answer in the rospy source. There is a comment that explicitly states that sending of all messages before shutdown is not guaranteed. Instead, there is a check for whether the process is still running before writing, and if not it exits immediately.

Here is an excerpt from topics.py

 except ValueError:
        # operations on self.buff can fail if topic is closed
        # during publish, which often happens during Ctrl-C.
        # diagnose the error and report accordingly.
        if self.closed:
            if is_shutdown():
                # we offer no guarantees on publishes that occur
                # during shutdown, so this is not exceptional.
                return
edit flag offensive delete link more
1

answered 2014-07-07 15:48:34 -0500

fergs gravatar image

What is the actual semantics of the message being sent, does it have some set lifetime? One possible option here would be for the publisher to be set to "latched" and then have the node only sleep for the "valid lifetime" of the message that is latched. By latching the message, you avoid the issues with subscribers not connecting quickly enough between the time of advertisement and before publication of the message.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2014-07-03 12:48:32 -0500

Seen: 3,597 times

Last updated: Jul 09 '14