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

rospy.wait_for_message does not get the message even though new messages are being published

asked 2019-03-14 09:36:16 -0500

kump gravatar image

updated 2019-03-15 07:54:42 -0500

I'm running a script where I use the rospy.wait_for_message in a while loop to wait for a message of a topic, that is publishing at certain event.

On the first event the while loop runs as expected, sometimes even on the second. I can see by running rostopic echo /event_topic that the messages are being published after the code stopped inside the while loop at the instruction rospy.wait_for_message("/event_topic", Bool, timeout=None), but the instruction is never executed. The program just stays at this line, waiting for messages, that are being published.

When I reset the script the first one or two events are again processed as expected and that the process halts. I cannot find any errors nor warnings printed in the terminal.

This is my script:

import rospy
import rospkg
from std_msgs.msg import Bool
from std_msgs.msg import Float64
from std_msgs.msg import Float32MultiArray

def mynode():
    rospy.init_node('mynode')
    publisher = rospy.Publisher('/command', Float64, queue_size=1)

    time.sleep(.5)

    while not rospy.is_shutdown():
        rospy.wait_for_message("/event_topic", Bool, timeout=None)

        data = rospy.wait_for_message("/data_topic", Float32MultiArray, timeout=None)
        msg = data.data[0]

        publisher.publish(msg)
        time.sleep(.2) 
        rospy.spin()

if __name__ == '__main__':
    try:
        mynode()
    except rospy.ROSInterruptException:
        pass

It also seems, that when I subscribe to the /event_topic by running rostopic echo in the terminal, the next event is being processed by the rospy.wait_for_message, but following, again, are not.


EDIT

The problem is somehow connected to the multimaster-FKIE package. I run two simulations on two ROS masters and use the multimaster-FKIE package to allow communication between them. The node shown above is supposed to read messages from topics started in one ROS master and publish messages into the topics started in the other ROS master.

When I run the node on the ROS core where the /event_topic was started, it works as expected. If I run the node on the ROS master where the /data_topic was started, the problem occurs. But I don't understand why. The topics are supposed to be shared among the ROS masters.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2019-03-17 15:16:55 -0500

gvdhoorn gravatar image

You have this:

while not rospy.is_shutdown():
  [..]
  rospy.spin()

unless the intention to only ever run a single iteration of the while-loop, I don't believe that rospy.spin() should be there. It's essentially a non-returning statement (ie: your program will hang there indefinitely).

When I reset the script the first one or two events are again processed as expected and that the process halts.

If by "first two events" you mean two messages, then that could be explained by the fact that you have two rospy.wait_for_message(..) in a row, executed before your script reaches the blocking rospy.spin().

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2019-03-14 09:36:16 -0500

Seen: 90 times

Last updated: Mar 17 '19