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

Problems with boost::bind in a class with message_filter

asked 2020-04-30 07:45:00 -0500

Narton gravatar image

updated 2022-01-22 16:10:31 -0500

Evgeny gravatar image

Hello, I am attempting to use a class to synchronize subscription to a detection message [vision_msgs/Detection2DArray] and a camera_info message. I am getting compile errors when binding the TimeSynchronizer to the callback. I have viewed [https://answers.ros.org/question/1727...] but have not found any clues yet... The code and errors are below. Any help would be appreciated. Boost version 1.65.1, gcc version 7.5, ubuntu Bionic, Ros Melodic.

#include <ros/ros.h>
#include <image_geometry/pinhole_camera_model.h>
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include <vision_msgs/Detection2D.h>
#include <vision_msgs/Detection2DArray.h>
#include <vision_msgs/ObjectHypothesisWithPose.h>
#include <sensor_msgs/CameraInfo.h>

using namespace vision_msgs;

class myClass{
  public:
  myClass():sync(det_sub, info_sub, 20)
  { 
    det_sub.subscribe(nh, "det", 20);
    info_sub.subscribe(nh, "camera_info", 20);
    sync.registerCallback(boost::bind(&myClass::callback, _1, _2 ));
  }

  private:
  void callback(Detection2DArrayConstPtr& det,sensor_msgs::CameraInfoConstPtr& cam_info)
  {
      //do stuff

      //publish stuff
  }

  ros::NodeHandle nh;
  message_filters::Subscriber<Detection2DArray> det_sub;
  message_filters::Subscriber<sensor_msgs::CameraInfo> info_sub;
  message_filters::TimeSynchronizer<Detection2DArray,sensor_msgs::CameraInfo> sync;
  image_geometry::PinholeCameraModel cam_model;

};

int main(int argc, char** argv)
{
  ros::init(argc, argv, "vision_node");

  /* 
  //want this in a class -- it compiles fine on its own
  message_filters::Subscriber<Detection2DArray> det_sub(nh, "det", 1);
  message_filters::Subscriber<sensor_msgs::CameraInfo> info_sub(nh, "camera_info", 1);
  message_filters::TimeSynchronizer<Detection2DArray,
            sensor_msgs::CameraInfo> sync(det_sub, info_sub, 10);
  sync.registerCallback(boost::bind(&callback, _1, _2));*/
  myClass aTest;
  ros::spin();

  return 0;
}

the errors are:

In file included from /usr/include/boost/bind.hpp:22:0,
                 from /opt/ros/melodic/include/ros/publisher.h:35,
                 from /opt/ros/melodic/include/ros/node_handle.h:32,
                 from /opt/ros/melodic/include/ros/ros.h:45,
                 from /home/hrrnxt/Workspace/RosStuff/camera_ws/src/bbox_undistort/src/bbox_undistort_node.cpp:1:
/usr/include/boost/bind/bind.hpp: In instantiation of ‘struct boost::_bi::result_traits<boost::_bi::unspecified, void (myClass::*)(boost::shared_ptr<const vision_msgs::Detection2DArray_<std::allocator<void> > >&, boost::shared_ptr<const sensor_msgs::CameraInfo_<std::allocator<void> > >&)>’:
/usr/include/boost/bind/bind.hpp:1284:48:   required from ‘class boost::_bi::bind_t<boost::_bi::unspecified, void (myClass::*)(boost::shared_ptr<const vision_msgs::Detection2DArray_<std::allocator<void> > >&, boost::shared_ptr<const sensor_msgs::CameraInfo_<std::allocator<void> > >&), boost::_bi::list2<boost::arg<1>, boost::arg<2> > >’
/home/hrrnxt/Workspace/RosStuff/camera_ws/src/bbox_undistort/src/bbox_undistort_node.cpp:18:66:   required from here
/usr/include/boost/bind/bind.hpp:75:37: error: ‘void (myClass::*)(boost::shared_ptr<const vision_msgs::Detection2DArray_<std::allocator<void> > >&, boost::shared_ptr<const sensor_msgs::CameraInfo_<std::allocator<void> > >&)’ is not a class, struct, or union type
     typedef typename F::result_type type;
                                     ^~~~
In file included from /usr/include/boost/function/detail/maybe_include.hpp:58:0,
                 from /usr/include/boost/function/detail/function_iterate.hpp:14,
                 from /usr/include/boost/preprocessor/iteration/detail/iter/forward1.hpp:92,
                 from /usr/include/boost/function.hpp:64,
                 from /opt/ros/melodic/include/ros/forwards.h:40,
                 from /opt/ros/melodic/include/ros/common.h:37,
                 from /opt/ros/melodic/include/ros/ros.h:43,
                 from /home/hrrnxt/Workspace/RosStuff/camera_ws/src/bbox_undistort/src/bbox_undistort_node.cpp:1:
/usr/include/boost/function/function_template.hpp: In instantiation of ‘static void boost::detail::function::void_function_obj_invoker9<FunctionObj, R, T0, T1, T2, T3, T4, T5, T6 ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
2

answered 2020-04-30 10:23:28 -0500

Thomas D gravatar image

There are two problems.

The parameters to your callback function must be declared const. Change from

void callback(Detection2DArrayConstPtr& det,sensor_msgs::CameraInfoConstPtr& cam_info)

to

void callback(const Detection2DArrayConstPtr& det, const sensor_msgs::CameraInfoConstPtr& cam_info)

Pass this to bind. Change from

sync.registerCallback(boost::bind(&myClass::callback, _1, _2 ));

to

sync.registerCallback(boost::bind(&myClass::callback, this, _1, _2 ));
edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2020-04-30 07:45:00 -0500

Seen: 1,297 times

Last updated: Apr 30 '20