0
$\begingroup$

Rosanswers logo

To my surprise, the following simple program

#include "ros/ros.h"
#include "std_msgs/Int32.h"

int main(int argc, char** argv)
{
    ros::init(argc, argv, "test");

    ros::NodeHandle nh;
    std_msgs::Int32::ConstPtr ret;
    ret = ros::topic::waitForMessage<std_msgs::Int32>("/topic");
    ROS_INFO("%d", ret->data);
    ret = ros::topic::waitForMessage<std_msgs::Int32>("/topic");
    ROS_INFO("%d", ret->data);
    ret = ros::topic::waitForMessage<std_msgs::Int32>("/topic");
    ROS_INFO("%d", ret->data);

    ros::spin();

    return 0;
}

Prints 3 0s when I run a single rostopic pub /topic std_msgs/Int32 "data: 0".

One workaround is to add a ros::Duration(1).sleep() between the waits but that doesn't work for my situation.

How can I have waitForMessage actually wait for 3 publishes, provided that I don't know the interval between publishes?


Originally posted by Rufus on ROS Answers with karma: 1083 on 2020-12-29

Post score: 0

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

To my surprise, the following simple program: [..] Prints 3 0s when I run a single rostopic pub /topic std_msgs/Int32 "data: 0".

The behaviour you observe is actually as it should be, and the cause is not waitForMessage(..) doing something "wrong", but your expectations are incorrect.

The following is the output of the command you ran:

$ rostopic pub /topic std_msgs/Int32 "data: 0"
publishing and latching message. Press ctrl-C to terminate

Notice the "and latching message" part of what rostopic pub prints.

Latched publishers (wiki/roscpp/Overview/Publishers and Subscribers - Publisher Options) will republish the last published message upon subscription by new subscribers, even if those subscribers were not online when the initial message was published.

So in your case, rostopic pub publishes "the 0" once when it is started, and then subsequently again for every ros::Subscriber created by ros::topic::waitForMessage(..) (as that function creates a new subsciber every time it is run).

Receiving the same message with every waitForMessage(..) seems to be as it should.

One workaround is to add a ros::Duration(1).sleep() between the waits [..]

That would surprise me actually, as that's not how latched publishers work.

How can I have waitForMessage actually wait for 3 publishes, provided that I don't know the interval between publishes?

I wouldn't know, as that's not what that function is for. How would it distinguish between "the same 0" and another message, which happens to also carry a 0?

As a final comment: please note that waitForMessage(..) is not intended to be used to periodically "sample" a message stream, or to implement some sort of rate-limiter (ie: calling waitForMessage(..) repeatedly in a while loop with a ros::Rate or something similar).

It is a fairly costly operation which is typically only used to get some initial state from a topic, or when really only a single message is needed for some reason.

In almost all other cases it would be better to use something like message_filters and/or regular subscribers.


Originally posted by gvdhoorn with karma: 86574 on 2020-12-29

This answer was ACCEPTED on the original site

Post score: 2


Original comments

Comment by Rufus on 2020-12-30:
Further testing shows the sleep workaround doesn't actually work.

Comment by Rufus on 2020-12-30:
Curiously, it appears waitForMessage does not work as expected for non-latching messages, even if waitForMessage occurs before the publishing of the non-latching message, I've asked that as a separate question

Comment by gvdhoorn on 2020-12-30:\

Curiously, it appears waitForMessage does not work as expected for non-latching messages, even if waitForMessage occurs before the publishing of the non-latching message

waitForMessage(..) works fine for "non latched messages".

Perhaps you are expecting things to work in a way they don't.

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.