Using boost::bind to pass additional arguments to my subscriber callback fails
I'm trying to pass additional arguments to my Subscriber callback function. I already found a good post on how to this here. At least it looks like a good post to me, but unfortunately it doesn't work. I'm also using a class and I want to use a member function of that class as the callback function of the subscriber. My class definition is as follows:
#include <vector>
#include "ros/ros.h"
#include "sensor_msgs/Image.h"
class DataProcessor
{
public:
DataProcessor(
ros::NodeHandle n=ros::NodeHandle(),
ros::NodeHandle priv_n=ros::NodeHandle("~"));
private:
ros::NodeHandle nh;
ros::NodeHandle priv_nh;
ros::Subscriber color_subscriber;
ros::Subscriber ir_subscriber;
ros::Subscriber depth_subscriber;
std::vector<sensor_msgs::Image> color_container;
std::vector<sensor_msgs::Image> ir_container;
std::vector<sensor_msgs::Image> depth_container;
void storeData(const sensor_msgs::Image & msg,
std::vector<sensor_msgs::Image> & container);
};
Then in the constructor of that class I'm trying to pass a class member additionally to the subscriber function like this:
#include <functional>
#include <boost/bind.hpp>
#include "data_processor.h"
DataProcessor::DataProcessor(ros::NodeHandle n,
ros::NodeHandle priv_n) :
nh(n),
priv_nh(priv_n)
{
ir_subscriber=nh.subscribe<sensor_msgs::Image>
("/kinect2/qhd/image_depth_rect",
1e3,
boost::bind(&DataProcessor::storeData,this,boost::placeholders::_1,ir_container));
}
void DataProcessor::storeData(const sensor_msgs::Image & msg,
std::vector<sensor_msgs::Image> & container) {
container.push_back(msg);
}
As far as I can see it, this subscriber call looks exactly like the one in the linked post, but I get a compilation error as follows:
/usr/include/boost/bind/bind.hpp:398: error: no match for call to '(boost::_mfi::mf2<void, DataProcessor, const sensor_msgs::Image_<std::allocator<void> >&, std::vector<sensor_msgs::Image_<std::allocator<void> > >&>) (DataProcessor*&, const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, std::vector<sensor_msgs::Image_<std::allocator<void> > >&)'
unwrapper<F>::unwrap(f, 0)(a[base_type::a1_], a[base_type::a2_], a[base_type::a3_]);
~~~~~~~~~~~~~~~~~~~~~~~~~~^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
Maybe try changing your callback signature to have the first arg be
const sensor_msgs::ImageConstPtr
@jarvisschultz Now the code compiles! But the topic doesn't publish this type of message, it publishes
sensor_msgs::Image
. Will it work anyway?I just switched to a different valid callback signature... it's still the same topic. http://wiki.ros.org/roscpp/Overview/P...
The biggest difference is that now you'd have a
boost::shared_ptr
instead of a reference to an object. So you'd have to usemsg->header
instead ofmsg.header