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

Using arguments in callback function of image_transport::ImageTransport::subscribeCamera or pass a pointer

asked 2012-06-27 02:53:34 -0500

cduguet gravatar image

updated 2014-01-28 17:12:49 -0500

ngrennan gravatar image

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 ...
(more)
edit retag flag offensive close merge delete

3 Answers

Sort by » oldest newest most voted
1

answered 2012-06-27 03:18:53 -0500

dornhege gravatar image

updated 2012-06-27 03:23:52 -0500

In short, remove the _2 parameter then you should get what you desire.
This will call your callback using the received message as the first parameter and cv_pref_ptr as the second.

Depending on how you desire to use the pointer you might want to use boost::ref to pass the pointer as reference (if you want to change the pointer, not the pointed object). Also as it is now the cv_pref_ptr is declared locally and thus will go out of scope.

Is there anything that prevents you from making the cv_pref_ptr a member variable of the class?

edit flag offensive delete link more
0

answered 2012-06-27 04:31:48 -0500

cduguet gravatar image

Hi dornedge!

Particularly the subscribeCamera callback function needs two arguments, one for the message itself and the second for sensor_msgs::CameraInfoConstPtr& info_msg ,so cv_ptr_prev must be the 3rd argument. That is why I used it with _1 and _2.

Anyway, foolish from me, yes! there's nothing stopping it from declaring it as a member variable!, and that way is the problem solved! :):) Many thanks!

edit flag offensive delete link more
0

answered 2016-05-03 10:57:44 -0500

lucasw gravatar image

updated 2016-05-03 11:38:22 -0500

this is in the wrong place:

image_sub = transport.subscribeCamera("/camera/image_raw", 1, boost::bind(&Optical_Flow::flowcallback, this, _1, _2, cv_ptr_prev));

I have a complete code example in my answer to http://answers.ros.org/question/23345...

edit flag offensive delete link more

Question Tools

Stats

Asked: 2012-06-27 02:53:34 -0500

Seen: 3,950 times

Last updated: May 03 '16