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

subscribe to callback which takes arguments and transport hints

asked 2019-02-17 12:07:12 -0500

mcamurri gravatar image

updated 2019-02-18 04:32:26 -0500

Hi all, I'm subscribing to a callback which takes arguments by using the boost::bind structure:

nh_.subscribe<MsgT>(topic, 1000,  boost::bind(&ROSFrontEnd::callback<MsgT>, this, _1, sensor_id));

where the callback signature is the follwing:

template <class MsgT>
void callback(boost::shared_ptr<MsgT const> msg,
              const SensorId& Key);

Now I want to extend the subscription by adding transport hints, like so:

nh_.subscribe<MsgT>(topic, 1000,  boost::bind(&ROSFrontEnd::callback<MsgT>, this, _1, sensor_id), ros::TransportHints().tcpNoDelay());

but I get a compilation error saying that there is no such signature for subscribe.

What is the correct way to subscribe to a callback taking arguments and passing transport hints as well?

The code worked just fine without the transport hints. I'm using Ubuntu 16.04 with ROS Kinetic.

UPDATE Here is a MCVE with the full error listing:

#include <boost/shared_ptr.hpp>
#include <boost/bind.hpp>
#include <std_msgs/String.h>
#include <ros/node_handle.h>
#include <ros/subscriber.h>
#include <ros/transport_hints.h>

class TransportHintsTest {
public:
    typedef std::string SensorId;
public:

    TransportHintsTest(ros::NodeHandle& nh) : nh_(nh){

        SensorId id = "string";
        sub = nh_.subscribe<std_msgs::String>("mytopic", 10, boost::bind(&TransportHintsTest::callback<std_msgs::String>,
                                                                         this,
                                                                         _1,
                                                                         id),
                                              ros::TransportHints().tcpNoDelay()); // without this last argument, compiles fine
    }

    template <class MsgT>
    void callback(boost::shared_ptr<MsgT const> msg, const SensorId& sensor_id){
    }

private:
    ros::Subscriber sub;
    ros::NodeHandle nh_;
};

int main(int argc, char** argv) {
    ros::init(argc, argv,"transport_hint_test");
    ros::NodeHandle nh;
    TransportHintsTest node(nh);
}

The error says:

/home/mcamurri/catkin_ws/src/transport_hint_test/src/transport_hints.cpp: In constructor ‘TransportHintsTest::TransportHintsTest(ros::NodeHandle&)’:
/home/mcamurri/catkin_ws/src/transport_hint_test/src/transport_hints.cpp:20:81: error: no matching function for call to ‘ros::NodeHandle::subscribe(const char [8], int, boost::_bi::bind_t<void, boost::_mfi::mf2<void, TransportHintsTest, boost::shared_ptr<const std_msgs::String_<std::allocator<void> > >, const std::__cxx11::basic_string<char>&>, boost::_bi::list3<boost::_bi::value<TransportHintsTest*>, boost::arg<1>, boost::_bi::value<std::__cxx11::basic_string<char> > > >, ros::TransportHints&)’
                                               ros::TransportHints().tcpNoDelay());
                                                                                 ^
In file included from /home/mcamurri/catkin_ws/src/transport_hint_test/src/transport_hints.cpp:4:0:
/opt/ros/kinetic/include/ros/node_handle.h:402:14: note: candidate: template<class M, class T> ros::Subscriber ros::NodeHandle::subscribe(const string&, uint32_t, void (T::*)(M), T*, const ros::TransportHints&)
   Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M), T* obj, 
              ^
/opt/ros/kinetic/include/ros/node_handle.h:402:14: note:   template argument deduction/substitution failed:
/home/mcamurri/catkin_ws/src/transport_hint_test/src/transport_hints.cpp:20:81: note:   mismatched types ‘void (T::*)(std_msgs::String_<std::allocator<void> >)’ and ‘boost::_bi::bind_t<void, boost::_mfi::mf2<void, TransportHintsTest, boost::shared_ptr<const std_msgs::String_<std::allocator<void> > >, const std::__cxx11::basic_string<char>&>, boost::_bi::list3<boost::_bi::value<TransportHintsTest*>, boost::arg<1>, boost::_bi::value<std::__cxx11::basic_string<char> > > >’
                                               ros::TransportHints().tcpNoDelay());
                                                                                 ^
In file included from /home/mcamurri/catkin_ws/src/transport_hint_test/src/transport_hints.cpp:4:0:
/opt/ros/kinetic/include/ros/node_handle.h:413:14: note: candidate: template<class M, class T> ros::Subscriber ros::NodeHandle::subscribe ...
(more)
edit retag flag offensive close merge delete

Comments

1

Can you post the full error message please, we need to see all the detail to be able to help you.

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2019-02-18 03:21:20 -0500 )edit

I've added a minimal example with full error output.

mcamurri gravatar image mcamurri  ( 2019-02-18 04:28:16 -0500 )edit

1 Answer

Sort by » oldest newest most voted
2

answered 2019-02-18 04:45:52 -0500

aPonza gravatar image

updated 2019-02-18 04:47:31 -0500

From the API docs it seems that all the boost::bind versions (11 and 12 out of 13) require you to also specify the tracked object:

tracked_object: A shared pointer to an object to track for these callbacks. If set, the a weak_ptr will be created to this object, and if the reference count goes to 0 the subscriber callbacks will not get called. Note that setting this will cause a new reference to be added to the object before the callback, and for it to go out of scope (and potentially be deleted) in the code path (and therefore thread) that the callback is invoked from.

The default seems to be typedef boost::shared_ptr<void const> ros::VoidConstPtr, i.e. this compiles:

#include <ros/forwards.h>

    sub = nh_.subscribe<std_msgs::String>("mytopic", 10, boost::bind(&TransportHintsTest::callback<std_msgs::String>,
                                                                     this,
                                                                     _1,
                                                                     id),
                                          ros::VoidConstPtr(),
                                          ros::TransportHints().tcpNoDelay());
edit flag offensive delete link more

Comments

Thank you! It works!

mcamurri gravatar image mcamurri  ( 2019-02-18 06:15:51 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2019-02-17 12:07:12 -0500

Seen: 1,278 times

Last updated: Feb 18 '19