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

Revision history [back]

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();
}