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

Revision history [back]

click to hide/show revision 1
initial version

Use a ros::MessageEvent type callback:

http://www.ros.org/wiki/roscpp/Overview/Publishers%20and%20Subscribers#MessageEvent_.5BROS_1.1.2B-.5D

void callback(const ros::MessageEvent<std_msgs::String const>& event)
{
  const ros::M_string& header = event.getConnectionHeader();
  std::string topic = header["topic"];

  const std_msgs::StringConstPtr& msg = event.getMessage();
}

Something like the above code might work.

There is a related mailing list thread:

http://ros-users.122217.n3.nabble.com/How-to-identify-the-subscriber-or-the-topic-name-related-to-a-callback-td2391327.html

Like the thread suggests, it's probably easier to encode this information into the creation of the subscriber:

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

#include <sstream>

void callback(const std_msgs::String::ConstPtr &msg, const std::string &topic) {
    ; // Do stuff
}

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

  ros::NodeHandle n;

  ros::Subscriber sub1 = n.subscribe<std_msgs::String>("foo", 1, boost::bind(callback, _1, "foo"));
  ros::Subscriber sub2 = n.subscribe<std_msgs::String>("bar", 1, boost::bind(callback, _1, "bar"));

  return 0;
}

Use a ros::MessageEvent type callback:

http://www.ros.org/wiki/roscpp/Overview/Publishers%20and%20Subscribers#MessageEvent_.5BROS_1.1.2B-.5D

void callback(const ros::MessageEvent<std_msgs::String const>& event)
{
  const ros::M_string& header = event.getConnectionHeader();
  std::string topic = header["topic"];
header.at("topic");

  const std_msgs::StringConstPtr& msg = event.getMessage();
}

Something like the above code might should work.

There is a related mailing list thread:

http://ros-users.122217.n3.nabble.com/How-to-identify-the-subscriber-or-the-topic-name-related-to-a-callback-td2391327.html

Like the thread suggests, it's probably easier to encode this information into the creation of the subscriber:

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

#include <sstream>

void callback(const std_msgs::String::ConstPtr &msg, const std::string &topic) {
    ; // Do stuff
}

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

  ros::NodeHandle n;

  ros::Subscriber sub1 = n.subscribe<std_msgs::String>("foo", 1, boost::bind(callback, _1, "foo"));
  ros::Subscriber sub2 = n.subscribe<std_msgs::String>("bar", 1, boost::bind(callback, _1, "bar"));

  return 0;
}

Use a ros::MessageEvent type callback:

http://www.ros.org/wiki/roscpp/Overview/Publishers%20and%20Subscribers#MessageEvent_.5BROS_1.1.2B-.5D

void callback(const ros::MessageEvent<std_msgs::String const>& event)
{
  const ros::M_string& header = event.getConnectionHeader();
  std::string topic = header.at("topic");

  const std_msgs::StringConstPtr& msg = event.getMessage();
}

Something like the above code should work.BUT THE ABOVE CODE MIGHT NOT WORK!

There is a related mailing list thread:

http://ros-users.122217.n3.nabble.com/How-to-identify-the-subscriber-or-the-topic-name-related-to-a-callback-td2391327.html

Like The thread mentions that the topic component of the ConnectionHeader is not always set. So, like the thread suggests, it's probably easier to encode this information into the creation of the subscriber:

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

#include <sstream>

void callback(const std_msgs::String::ConstPtr &msg, const std::string &topic) {
    ; // Do stuff
}

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

  ros::NodeHandle n;

  ros::Subscriber sub1 = n.subscribe<std_msgs::String>("foo", 1, boost::bind(callback, _1, "foo"));
  ros::Subscriber sub2 = n.subscribe<std_msgs::String>("bar", 1, boost::bind(callback, _1, "bar"));

  return 0;
}