Using arguments in callback function of image_transport::ImageTransport::subscribeCamera or pass a pointer
Hi, I need to use two continuous images in order to calculate the Optical Flow between them. I created the Optical_Flow class, in which the subscriber to the Camera images calls its member function Optical_Flow::flowcallback to calculate the flow between the grabbed image and a previous one (whose pointer is the argument I want to give). So, inside flowcallback we will create cv_ptr and use cv_ptr_prev to make our calculations.
I have read that you can use boost::bind for this purpose, so that way the instantiated function just asks for the rest of the arguments. The implementation of the subscribeCamera is a little bit different, as it takes one more argument, and my implementations looks like this:
class Optical_Flow
{
ros::NodeHandle node;
image_transport::ImageTransport transport;
image_transport::CameraSubscriber image_sub;
image_transport::Publisher image_pub;
public:
Optical_Flow() : transport(node)
{
cv_bridge::CvImagePtr cv_ptr_prev;
image_pub = transport.advertise("out", 1);
image_sub = transport.subscribeCamera("/camera/image_raw", 1, boost::bind(&Optical_Flow::flowcallback,_1,_2,cv_ptr_prev), this);
...
}
void flowcallback(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& info_msg, cv_bridge::CvImagePtr cv_ptr_prev)
{
//Create cv_ptr and determine flow from image cv_ptr_prev
}
};
The problem is, that it gives me the following error messages:
/usr/include/boost/bind/bind.hpp:69:37: error: ‘void (Optical_Flow::*)(const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, const boost::shared_ptr<const sensor_msgs::CameraInfo_<std::allocator<void> > >&, boost::shared_ptr<cv_bridge::CvImage>)’ is not a class, struct, or union type
...
.../OpticalFlow/src/Optical_Flow.cpp:75:130: error: no matching function for call to ‘image_transport::ImageTransport::subscribeCamera(const char [18], int, boost::_bi::bind_t<boost::_bi::unspecified, void (Optical_Flow::*)(const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, const boost::shared_ptr<const sensor_msgs::CameraInfo_<std::allocator<void> > >&, boost::shared_ptr<cv_bridge::CvImage>), boost::_bi::list3<boost::arg<1>, boost::arg<2>, boost::_bi::value<boost::shared_ptr<cv_bridge::CvImage> > > >, Optical_Flow* const)’
/OpticalFlow/src/Optical_Flow.cpp:75:130: note: candidates are:
/opt/ros/fuerte/stacks/image_common/image_transport/include/image_transport/image_transport.h:103:20: note: image_transport::CameraSubscriber image_transport::ImageTransport::subscribeCamera(const string&, uint32_t, const Callback&, const VoidPtr&, const image_transport::TransportHints&)
/opt/ros/fuerte/stacks/image_common/image_transport/include/image_transport/image_transport.h:103:20: note: no known conversion for argument 4 from ‘Optical_Flow* const’ to ‘const VoidPtr& {aka const boost::shared_ptr<void>&}’
/opt/ros/fuerte/stacks/image_common/image_transport/include/image_transport/image_transport.h:111:20: note: image_transport::CameraSubscriber image_transport::ImageTransport::subscribeCamera(const string&, uint32_t, void (*)(const ImageConstPtr&, const CameraInfoConstPtr&), const image_transport::TransportHints&)
/opt/ros/fuerte/stacks/image_common/image_transport/include/image_transport/image_transport.h:111:20: note: no known conversion for argument 3 from ‘boost::_bi::bind_t<boost::_bi::unspecified, void (Optical_Flow::*)(const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, const boost::shared_ptr<const sensor_msgs::CameraInfo_<std::allocator<void> > >&, boost::shared_ptr<cv_bridge::CvImage>), boost::_bi::list3<boost::arg<1>, boost::arg<2>, boost::_bi::value<boost::shared_ptr<cv_bridge::CvImage> > > >’ to ‘void (*)(const ImageConstPtr&, const CameraInfoConstPtr&) {aka void (*)(const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&, const boost::shared_ptr<const sensor_msgs::CameraInfo_<std::allocator<void> > >&)}’
/opt/ros/fuerte/stacks/image_common/image_transport/include/image_transport/image_transport.h:125:20 ...