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

boost bind additional arguments to CameraSubscriber class method callback?

asked 2016-05-02 14:46:13 -0500

lucasw gravatar image

updated 2020-11-21 12:08:31 -0500

CameraSubscriber callbacks have two arguments, one for the Image and the second for the CameraInfo- how to add a third argument and bind a value to it within subscribeCamera?

http://answers.ros.org/question/37378... was asking the same thing, but the solution was not to pass a parameter, and the other part of the answer did not realize the difference between subscribeCamera and subscribe.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
3

answered 2016-05-03 02:24:23 -0500

croesmann gravatar image

regarding your reference question, it doesn't matter with boost bind if you replace or add parameters. It's just a matter of using the placeholders _1, _2, ... provided by boost for forwarding the original arguments or by providing your own ones.

Here you can find another answer in which two extra parameters are added (next to _1): LINK.

Regarding the difference between subscribeCamera and subscribe: both functions provide an overload that excepts the a boost::function type callback, therefore you can apply boost::bind to both of them.

Refer to the Code Doc for the overloaded methods:

subscribeCamera (const std::string &base_topic, uint32_t queue_size, const CameraSubscriber::Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())

subscribe (const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())

Here the argument type CameraSubscriber::Callback is a typedef for a boost::function object accepting both default parameters. Pass your functor created with boost::bind here.

edit flag offensive delete link more
1

answered 2016-05-03 11:31:42 -0500

lucasw gravatar image

The answer to the referenced question was that this was in the wrong place- this is an 4th parameter to subscribe variant after the callback class method, but then it moves to inside boost::bind() when passing in additional parameters is required.

I wasn't actually making that mistake, but the difference was confusing enough I didn't realize that (and the compilation error was the same)- getting the _1 and _2 correct as @croesmann points out was the key. Here are some different examples.

#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>
#include <ros/ros.h>
#include <sensor_msgs/CameraInfo.h>
#include <sensor_msgs/Image.h>

class CamSub
{
protected:
  bool restrict_size_;

  ros::NodeHandle nh_;
  image_transport::ImageTransport it_;
  image_transport::CameraSubscriber sub_1_;
  image_transport::CameraSubscriber sub_2_;
  image_transport::Subscriber sub_3_;

  void imageCallback1(const sensor_msgs::ImageConstPtr& msg,
      const sensor_msgs::CameraInfoConstPtr& ci,
      const int ind) {}
   void imageCallback2(const sensor_msgs::ImageConstPtr& msg,
      const sensor_msgs::CameraInfoConstPtr& ci) {}
   void imageCallback3(const sensor_msgs::ImageConstPtr& msg,
      const int ind) {}
public:
  CamSub();
};

CamSub::CamSub() :
  it_(nh_)
{
  const uint32_t queue_size = 1;
  const int ind = 5;
  sub_1_ = it_.subscribeCamera("image", queue_size,
      boost::bind(&CamSub::imageCallback1, this, _1, _2, ind));
  sub_2_ = it_.subscribeCamera("image", queue_size,
      &CamSub::imageCallback2,
      this);
  sub_3_ = it_.subscribe("image", queue_size,
      boost::bind(&CamSub::imageCallback3, this, _1, ind));
}
int main(int argc, char** argv)
{
  ros::init(argc, argv, "cam_sub");
  CamSub cam_sub;
  ros::spin();
}
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2016-05-02 14:46:13 -0500

Seen: 3,665 times

Last updated: May 03 '16