[ros-users] NodeHandle.subscribe(...) - callbacks

Ken Tossell ktossell at umd.edu
Sun Jul 4 15:04:37 UTC 2010


> Ideally I would like to add an argument to the subCallback method.
> For example:
> void chatterCallback(int queue_id, const std_msgs::StringConstPtr& msg)
> With queue_id being an int I defined when subscribing. Could I do that with my own boost::bind(...)? If so, how?

You can create a function binding that includes an identifier. ROS
won't have any knowledge of the extra parameter:

void callback(const Message::ConstPtr& msg, int queue_id) {
  ...
}

Subscriber subA = node.subscribe<Message>("topic1", 100,
boost::bind(callback, _1, 1));
Subscriber subB = node.subscribe<Message>("topic2", 100,
boost::bind(callback, _1, 2));

Or for a class member function:

Subscriber subA = node.subscribe<Message>("topic1", 100,
boost::bind(&Me::callback, this, _1, 1));
Subscriber subB = node.subscribe<Message>("topic2", 100,
boost::bind(&Me::callback, this, _1, 2));

I don't think the order of the parameters matters.

 - Ken



More information about the ros-users mailing list