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

Rospy publish is unreliable

asked 2018-05-19 19:04:06 -0500

Cerin gravatar image

I'm seeing something real strange involving a rospy Publisher.

When I run a rospy node on a development machine (not the robot), messages sent by a publisher may or may not be received by the master running on the robot. The problem seems to resolve itself after a few hours, leading me to believe it's some sort of obscure socket or port issue, but the problem is making rospy almost impossible to use.

Oddly enough, it seems to be isolated to just rospy, not other tools like rostopic.

For example, in my rospy node, running on the development machine, I was sending a message like:

    from std_msgs.msg import Int16
    pub = rospy.Publisher('/torso_arduino/motor_rotate', Int16, queue_size=1)
    pub.publish(Int16(-45))

It was working for a while, then I had to kill my node and restart to fix a bug. After the restart, no messages sent to that topic were received by that remote node running on the robot.

Just to ensure I wasn't losing my mind, on my development machine, I ran the equivalent rostopic command:

export ROS_MASTER_URI=http://robot:11311; rostopic pub --once /torso_arduino/motor_rotate std_msgs/Int16 -- -45

and sure enough, that was received. So then I modified my rospy node to run:

os.system('export ROS_MASTER_URI=http://robot:11311; rostopic pub --once /torso_arduino/motor_rotate std_msgs/Int16 -- -45')

and again, that also worked, but yet if I use rospy, it doesn't work.

My node's code is:

#!/usr/bin/env python
import time
import rospy
from std_msgs.msg import Int16

class MyNode(object):

    def __init__(self, **kwargs):
        rospy.init_node('dock_node', log_level=rospy.DEBUG)
        print('Rotating...')
        pub = rospy.Publisher('/torso_arduino/motor_rotate', Int16, queue_size=1)
        pub.publish(Int16(-45))
        # import os
        # os.system('rostopic pub --once /torso_arduino/motor_rotate std_msgs/Int16 -- -45')
        time.sleep(10)

if __name__ == '__main__':
    MyNode()

I'm running my node like:

export ROS_MASTER_URI=http://robot:11311; rosrun myrobot mynode.py

and the terminal output is:

[DEBUG] [2018-05-19 19:42:14]: init_node, name[/mynode], pid[5769]
[DEBUG] [2018-05-19 19:42:14]: binding to 0.0.0.0 0
[DEBUG] [2018-05-19 19:42:14]: bound to 0.0.0.0 43289
[DEBUG] [2018-05-19 19:42:14]: ... service URL is rosrpc://localhost:43289
[DEBUG] [2018-05-19 19:42:14]: [/mynode/get_loggers]: new Service instance
[DEBUG] [2018-05-19 19:42:14]: ... service URL is rosrpc://localhost:43289
[DEBUG] [2018-05-19 19:42:14]: [/mynode/set_logger_level]: new Service instance
Rotating...
[DEBUG] [2018-05-19 19:42:25]: TCPServer[43289] shutting down

What am I doing wrong?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2018-05-19 20:16:44 -0500

ahendrix gravatar image

Your publisher isn't waiting long enough for the topic to be connected before it sends a message; and if the subscriber isn't connected when you publish, it won't receive the message. This is a common mistake and there are many questions and answers about it; this one explains it in more detail: https://answers.ros.org/question/1075...

In addition to the answers proposed on that question, you could call get_num_connections on your publisher until at least one subscriber is connected, before you publish:

pub = rospy.Publisher('/torso_arduino/motor_rotate', Int16, queue_size=1)
while pub.get_num_connections() == 0:
    rospy.loginfo("Waiting for subscriber to connect")
    rospy.sleep(1)
pub.publish(Int16(-45))

The rostopic command-line tool is also written using rospy, and is has a similar startup delay between the creation of the publisher and the first call to publish()

edit flag offensive delete link more

Comments

That makes sense. I haven't run into this earlier because in my other nodes I usually initialize the publishers long before I use them, so that wait happened implicitly. Thanks.

Cerin gravatar image Cerin  ( 2018-05-19 20:34:31 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2018-05-19 19:04:06 -0500

Seen: 2,410 times

Last updated: May 19 '18