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

Get topic name in callback?

asked 2013-07-23 11:02:10 -0500

Tom Moore gravatar image

I have multiple subscriptions to messages of the same type. I want to use the same callback method for all of them, but I'd like to know which topic the message "came from" when the callback is executed. I found some examples online that use boost::bind, but rosmake is not happy with the syntax, and I'm beginning to wonder if they're from an older version of ROS. I also tried using MessageEvent's getConnectionHeader(), but the returned map doesn't contain a value for the key "topic." This seems like it ought to be something that should be readily available. Any ideas? I have to be missing something obvious.

edit retag flag offensive close merge delete

Comments

A duplicate of [my question](http://answers.ros.org/question/51706/using-a-callback-for-multiple-subscribers-emulating-physical-outputs/). The answer is what @William told you to do, though.

thebyohazard gravatar image thebyohazard  ( 2013-07-24 08:50:12 -0500 )edit

3 Answers

Sort by ยป oldest newest most voted
6

answered 2013-07-23 21:16:31 -0500

William gravatar image

updated 2013-07-24 14:33:50 -0500

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();
}

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

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;
}
edit flag offensive delete link more

Comments

1

@TheWumpus - this answer is much better than the one I provided. I sure hope you switch and accept it instead =) If, like me, you haven't used boost::bind before, this description made it click for me: http://www.boost.org/doc/libs/1_54_0/libs/bind/bind.html#Purpose

lindzey gravatar image lindzey  ( 2013-07-23 21:45:52 -0500 )edit

1. As I noted in the original post, the MessageEvent method does not work: ros::M_string header = event.getConnectionHeader(); ROS_INFO_STREAM("Topic is: " << header["topic"] << " count of 'topic' key is " << header.count("topic")); Output: Topic is: count of 'topic' keys is 0

Tom Moore gravatar image Tom Moore  ( 2013-07-24 14:14:17 -0500 )edit

@TheWumpus Yeah, I see that they mentioned that in the mailing list thread from 2011. I think the reason for this is that the "ConnectionHeader" is what is received over the wire, and for efficiency reasons the topic is not always set.

William gravatar image William  ( 2013-07-24 14:25:11 -0500 )edit

2. I also read the thread for the second solution you posted, and attempted to implement it before posting, but I must be doing something wrong, as the compiler doesn't care for the overload. The code you posted gives me the same result.

Tom Moore gravatar image Tom Moore  ( 2013-07-24 14:27:57 -0500 )edit

@William According to @tbh, your second solution should work, but I need to fight with it some more.

Tom Moore gravatar image Tom Moore  ( 2013-07-24 14:28:51 -0500 )edit

@TheWumpus The second solution works for me too.

William gravatar image William  ( 2013-07-24 14:32:22 -0500 )edit

@William EDIT: Nevermind. I have it sorted. I'll accept this as the answer. Thank you (and you, @tbh)!

Tom Moore gravatar image Tom Moore  ( 2013-07-24 14:33:20 -0500 )edit

What would the boost bind approach look like with a class method callback? (where does 'this' go?)

lucasw gravatar image lucasw  ( 2015-03-11 19:56:25 -0500 )edit
3

answered 2013-07-23 11:42:49 -0500

updated 2013-07-23 11:59:48 -0500

With rospy, you can pass extra argument to a callback function, I think you could pass the topic_name. See this from the Subscriber Class:

class Subscriber Found at: rospy.topics

class Subscriber(Topic):
"""
Class for registering as a subscriber to a specified topic, where
the messages are of a given type.
"""
def __init__(self, name, data_class, callback=None, callback_args=None, 
    queue_size=None, buff_size=DEFAULT_BUFF_SIZE, tcp_nodelay=False):
    """
    [...]

    @param callback_args: additional arguments to pass to the
      callback. This is useful when you wish to reuse the same
      callback for multiple subscriptions.

I think with roscpp something similar exists

edit flag offensive delete link more
1

answered 2013-07-23 11:25:00 -0500

lindzey gravatar image

updated 2013-07-23 12:23:45 -0500

I hope somebody comes along with a more elegant solution, but here's the first (ugly, but easy) thing I thought of:

Write one helper function that contains the body of the callback you now have, and whose parameters are the message and a string identifying the source's topic name.

Write separate callback functions for each topic you subscribe to, each of which calls the helper function, passing along the message and adding the appropriate topic name.

EDIT: (assuming roscpp, based on the tags) If you don't know the topics ahead of time, can you define a class with two methods, one of which is the callback, and another that sets the topic? Then, for each topic that's passed in as a parameter, create an instance of your class, set the topic appropriately, and then set its callback function in the subscribe? Here's a tutorial with using class methods in a callback.

(if rospy, then go with gustavo.velascoh's answer - I originally looked, and couldn't quickly find, an equivalent for roscpp)

edit flag offensive delete link more

Comments

EDIT: This should work. I created a class with a member variable pointer back to my class and a name member variable. The class has a callback defined that calls my object, and passes in the name. Good idea, thanks!

Tom Moore gravatar image Tom Moore  ( 2013-07-23 11:34:04 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2013-07-23 11:02:10 -0500

Seen: 8,402 times

Last updated: Jul 24 '13