[ros-users] How to identify the subscriber or the topic name related to a callback

Brian Gerkey gerkey at willowgarage.com
Tue Feb 1 18:22:03 UTC 2011


On Mon, Jan 31, 2011 at 5:46 AM, Markus Bader <markus.bader at tuwien.ac.at> wrote:
> I have multiple subscriber calling the same callback function. How can
> I determinate within my callback function the related topic name?
> getPublisherName gives me the related publisher but not the topic?

hi Markus,

At the time that you make the subscription, you can arrange for the
topic to be passed into the callback, using boost::bind.  Appended
below is a simple example that demonstrates this.

	brian.

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

class MyClass
{
  public:
    std::vector<ros::Subscriber> subs;

    MyClass()
    {
      ros::NodeHandle n;
      std::vector<std::string> topics;
      topics.push_back("foo");
      topics.push_back("bar");
      for (unsigned int i = 0; i < topics.size(); i++)
      {
        subs.push_back(n.subscribe<std_msgs::String>(topics[i], 1000,
boost::bind(&MyClass::callback, this, _1, topics[i])));
      }
    }

    void callback(const ros::MessageEvent<std_msgs::String const>& event,
                  const std::string& topic)
    {
      const std::string& publisher_name = event.getPublisherName();
      ROS_INFO("publisher: %s\ttopic: %s",
               publisher_name.c_str(), topic.c_str());
    }
};

int
main(int argc, char** argv)
{
  ros::init(argc, argv, "mynode");
  MyClass m;
  ros::spin();
  return 0;
}



More information about the ros-users mailing list