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

boost::bind errors in subscriber callback functions

asked 2014-01-23 21:56:59 -0500

Mandar gravatar image

updated 2014-01-28 17:19:09 -0500

ngrennan gravatar image

Hey, Kind of newbie in using boost, and this is driving me crazy. I wanted to pass on the topicname to the callback function of subscriber, so I followed the various questions already asked and wrote the following: My callback function:

void write_enocean(const palgate_madynes_msg::EnOceanFrame& msg,std::string topic)

Subscriber:

sub[i] = nh.subscribe(Topiclist[i].name,1000,boost::bind(&write_enocean,_1,Topicname[i].name));

If I do this, I get the following error:

error: no matching function for call to ‘ros::NodeHandle::subscribe(std::string&, int, boost::_bi::bind_t<void, void (*)(const palgate_madynes_msg::EnOceanFrame_<std::allocator<void> >&, std::basic_string<char>), boost::_bi::list2<boost::arg<1>, boost::_bi::value<std::basic_string<char> > > >*)’

followed by the various candidates, and then:

node_handle.h:785:14: note:   candidate expects 1 argument, 3 provided

On the other hand, if write the subscriber as such:

 sub[i] = nh.subscribe<palgate_madynes_msg::EnOceanFrame>(Topiclist[i].name,1000,boost::bind(&write_enocean,_1,test));

I get the error:

/usr/include/boost/bind/bind.hpp:313:9: error: invalid initialization of reference of type ‘const palgate_madynes_msg::EnOceanFrame_<std::allocator<void> >&’ from expression of type ‘const boost::shared_ptr<const palgate_madynes_msg::EnOceanFrame_<std::allocator<void> > >’

What am I doing wrong with boost? My CMakeLists.text already includes the rosbuild_add_boost_directories() but gives me an error if write rosbuild_link_boost(topic_listener bind) saying it could not locate bind.

edit retag flag offensive close merge delete

Comments

It seems to have problems to pick the right overload. Does it help to move the bind into a boost::function.

dornhege gravatar image dornhege  ( 2014-01-24 00:27:42 -0500 )edit

I'm not sure I understand what you mean. Do I use it something like boost::function(bind, ...) or? I've not really used boost before, hence the confusion.

Mandar gravatar image Mandar  ( 2014-01-24 01:01:29 -0500 )edit

You can put the return of a bind in a boost::function and give that a specific function type. When playing around with bind and callbacks that helps to isolate the problem.

dornhege gravatar image dornhege  ( 2014-01-24 01:19:25 -0500 )edit

Might be missing a _1 as the third arg.

luc gravatar image luc  ( 2015-10-05 00:03:49 -0500 )edit

2 Answers

Sort by » oldest newest most voted
4

answered 2014-01-23 23:29:16 -0500

Wolf gravatar image

I would not mess with boost::bind in this case and put the callback function in a class in order for passing the context to it. Example:

class MySubscriber
{
  std::string po_topic_name;
  ros::Subscriber po_sub;

  void write_enocean( const palgate_madynes_msg::EnOceanFrame& msg )
  {
    // use po_topic_name as you like ...
  }
public:

  MySubscriber( ros::NodeHandle ao_nh, std::string ao_topic ) :
    po_topic_name( ao_topic )
  {
    po_sub = ao_nh.subscribe( ao_topic,1000, &MySubscriber::write_enocean, this );
  }
};

Now you just have to create an Instance of MySubscriber for each of your topics...

edit flag offensive delete link more

Comments

I'll try this out and report back in case of errors. Thanks!

Mandar gravatar image Mandar  ( 2014-01-24 00:30:13 -0500 )edit

I modified the example code you provided to follow the tutorial http://wiki.ros.org/roscpp_tutorials/Tutorials/UsingClassMethodsAsCallbacks more closely. This way, only the function write_enocean and the topic_name were in the class, while the subscriber was defined outside, rather than class method

Mandar gravatar image Mandar  ( 2014-01-24 01:34:20 -0500 )edit
2

answered 2014-01-24 01:34:16 -0500

You are using the wrong signature in your callback. Replace

void write_enocean(const palgate_madynes_msg::EnOceanFrame& msg,std::string topic)

with

void write_enocean(const palgate_madynes_msg::EnOceanFrame::ConstPtr& msg,std::string topic)
edit flag offensive delete link more

Comments

Wow, that was simple to fix. I wonder which method would be better to use - this answer or using classes as suggested by @Wolf.

Mandar gravatar image Mandar  ( 2014-01-24 02:39:45 -0500 )edit
2

How you design your classes is up to you. However, I recommend the ConstPtr variant in all cases, because passing shared pointers allows ROS to bypass serialization and use shared memory message transport in nodelets.

roehling gravatar image roehling  ( 2014-01-26 22:38:35 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2014-01-23 21:56:59 -0500

Seen: 7,112 times

Last updated: Jan 24 '14