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

callback function for advertise is not called

asked 2012-11-14 01:45:43 -0600

Benoit Larochelle gravatar image

updated 2012-11-14 02:21:33 -0600

I have a publisher node and I would like to get a callback when a subscriber connects. I followed the example in the documentation, but I get a compilation warning and no callback. For example, I start a rostopic echo before I launch my node, and I do receive the message, but the publisher is never notified that a subscriber connected.

Here is the warning:

In function ‘int main(int, char**)’: .../AppTestCallbackSubscription.cpp:20:88: warning: the address of ‘void connectCallback(const ros::SingleSubscriberPublisher&)’ will always evaluate as ‘true’ [-Waddress]

Here is the code:

#include <ros/ros.h>
#include <std_msgs/String.h>

//typedef boost::function<void(const SingleSubscriberPublisher&)> SubscriberStatusCallback;
void connectCallback(const ros::SingleSubscriberPublisher& pub)
{
    ROS_INFO("Subscriber connected");
}

int main(int argc, char** argv)
{
    const std::string TOPIC_NAME = "/foo";

    ros::init(argc, argv, "MyPublisher");

    ros::NodeHandle nh("~");

    // None of these two lines triggers the callback
    //ros::Publisher pub = nh.advertise<std_msgs::String>(TOPIC_NAME, 10, connectCallback, ros::SubscriberStatusCallback(), ros::VoidConstPtr(), false);
    ros::Publisher pub = nh.advertise<std_msgs::String>(TOPIC_NAME, 10, connectCallback);

    // Gives time to the subscribers to connect
    ros::Time maxTime(ros::Time::now()+ros::Duration(1)); // Will wait at most 1000 ms
    while(ros::Time::now()<maxTime)
    {
        ros::spinOnce();
    }

    std_msgs::String msg;
    msg.data = "Hello World!";
    pub.publish(msg);

    ROS_INFO("Message published");

    return 0;
}
edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
1

answered 2012-12-11 03:34:23 -0600

Benoit Larochelle gravatar image

updated 2012-12-11 03:37:09 -0600

Here is the solution found by @Lorenz and fixed (in the documentation) by @Dirk Thomas.

An explicit type cast is required in front of the callback function:

Instead of: handle.advertise<std_msgs::Empty>("my_topic", 1, connectCallback);

Use: handle.advertise<std_msgs::Empty>("my_topic", 1, (ros::SubscriberStatusCallback)connectCallback);

edit flag offensive delete link more
3

answered 2012-11-14 04:04:33 -0600

updated 2012-11-14 04:06:19 -0600

You are passing the callback pointer address as the bool latch parameter (3rd parameter in the advertise function) and the compiler is telling you that this will always evaluate to true. Here's the documentation where I got this from.

I'm not sure how to get the behavior you want, but what you did is definitely not the way to go.

edit flag offensive delete link more

Comments

1

Wow. Good catch. I would say to get the right method selected, either specify all parameters or at least the disconnect callback. Maybe, adding a & in front of connectCallback could also help. Or an explicit type cast.

Lorenz gravatar image Lorenz  ( 2012-11-14 04:54:50 -0600 )edit
1

I was also afraid of compiler ambiguity so I already tried passing in all parameters (commented out line above). No improvement though. Adding a & in front also did not work. However, an explicit type cast did the trick! @Lorenz, maybe you could write it as a new answer and I'll give you kudos :-)

Benoit Larochelle gravatar image Benoit Larochelle  ( 2012-11-14 20:44:43 -0600 )edit

Also, I'll file a ticket to update the documentation because it I did a copy-paste from it and it clearly didn't work

Benoit Larochelle gravatar image Benoit Larochelle  ( 2012-11-14 20:46:08 -0600 )edit
1
Benoit Larochelle gravatar image Benoit Larochelle  ( 2012-11-14 21:35:44 -0600 )edit
2

I think the karma should go to @georgebrinbeiro :) Btw. I just tried and I guess the problem is that SubscriberStatusCallback is a boost::function and the compiler doesn't cast to it correctly. Explicitly creating the right type is better than casting: SubscriberStatusCallback(connectCallback).

Lorenz gravatar image Lorenz  ( 2012-11-14 21:44:19 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2012-11-14 01:45:43 -0600

Seen: 1,370 times

Last updated: Oct 01 '13