ros::SubscribeOptions init does not take in object callback?

asked 2021-06-21 02:03:21 -0600

gyrados10 gravatar image

updated 2021-06-21 10:28:27 -0600

I am trying to do something like this but using classes

    void ChatterCallback(const std_msgs::String::ConstPtr& msg) {
      ROS_INFO(" I heard: [%s]", msg->data.c_str());
      std::this_thread::sleep_for(0.02s);
    }
    int main(int argc, char **argv) {
      ros::init(argc, argv, "listener");
      ros::NodeHandle n;
      ros::SubscribeOptions ops;
      ops.template init<std_msgs::String>("chatter", 1, ChatterCallback);
      ops.allow_concurrent_callbacks = true;
      ros::Subscriber sub1 = n.subscribe(ops);
      ros::MultiThreadedSpinner spinner(2);
      spinner.spin();
      return 0;
}

This my code approach but i am getting errors

  ClusteringBenchmarkEntry::ClusteringBenchmarkEntry()
  {
    mThread1 = std::make_shared<ROS_TopicThread>("/ecu_pcl");
    mThread2 = std::make_shared<ROS_TopicThread>("/velodyne_back/velodyne_points");
    mThread3 = std::make_shared<ROS_TopicThread>("/velodyne_center/velodyne_points");
    mThread4 = std::make_shared<ROS_TopicThread>("/velodyne_front/velodyne_points");

    mMasterthread = std::make_shared<MasterThread>( *mThread1, *mThread2, *mThread3, *mThread4 );
    init_subscription();
....
 }
  void ClusteringBenchmarkEntry::init_subscription()
  {
//mOps is a ros::SubscribeOptions class member
    mOps1.init<sensor_msgs::PointCloud2>(mThread1->get_topic_name(), 10, std::bind(&ROS_TopicThread::callback, std::ref(mThread1), _1) );
    mOps2.init<sensor_msgs::PointCloud2>(mThread2->get_topic_name(), 10, std::bind(&ROS_TopicThread::callback, std::ref(mThread2), _1) );
    mOps3.init<sensor_msgs::PointCloud2>(mThread3->get_topic_name(), 10, std::bind(&ROS_TopicThread::callback, std::ref(mThread3), _1) );
    mOps4.init<sensor_msgs::PointCloud2>(mThread4->get_topic_name(), 10, std::bind(&ROS_TopicThread::callback, std::ref(mThread4), _1) );
    mOps1.allow_concurrent_callbacks = true;
    mOps2.allow_concurrent_callbacks = true;
    mOps3.allow_concurrent_callbacks = true;
    mOps4.allow_concurrent_callbacks = true;
    mThread1->get_subscriber() = mNodehandler.subscribe(mOps1);
    mThread1->get_subscriber() = mNodehandler.subscribe(mOps2);
    mThread1->get_subscriber() = mNodehandler.subscribe(mOps3);
    mThread1->get_subscriber() = mNodehandler.subscribe(mOps4);
}
 void ROS_TopicThread::callback(const sensor_msgs::PointCloud2Ptr& sub_ros_ptr)
{
//stuff
}

How do i get it to work? The compilation errors i am getting are

/usr/include/boost/function/function_template.hpp:159:11: error: no match for call to ‘(std::_Bind<void (ocb::ROS_TopicThread::*(std::reference_wrapper<std::shared_ptr<ocb::ROS_TopicThread> >, boost::arg<1>))(const boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > >&)>) (const boost::shared_ptr<const sensor_msgs::PointCloud2_<std::allocator<void> > >&)’
           BOOST_FUNCTION_RETURN((*f)(BOOST_FUNCTION_ARGS));
           ^
In file included from /usr/include/boost/smart_ptr/detail/shared_count.hpp:38:0,
                 from /usr/include/boost/smart_ptr/shared_ptr.hpp:28,
                 from /usr/include/boost/shared_ptr.hpp:17,
                 from /opt/ros/melodic/include/ros/forwards.h:37,
                 from /opt/ros/melodic/include/ros/common.h:37,
                 from /opt/ros/melodic/include/ros/ros.h:43,
                 from /home/shane/catkin_ws/src/pcl_ros_custom/include/ROS_TopicThread.h:17,
                 from /home/shane/catkin_ws/src/pcl_ros_custom/include/ClusteringBenchmarkEntry.h:20,
                 from /home/shane/catkin_ws/src/pcl_ros_custom/src/ClusteringBenchmarkEntry.cpp:1:
/usr/include/c++/7/functional:547:2: note: candidate: template<class ... _Args, class _Result> _Result std::_Bind<_Functor(_Bound_args ...)>::operator()(_Args&& ...) [with _Args = {_Args ...}; _Result = _Result; _Functor = void (ocb::ROS_TopicThread::*)(const boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > >&); _Bound_args = {std::reference_wrapper<std::shared_ptr<ocb::ROS_TopicThread> >, boost::arg<1>}]
  operator()(_Args&&... __args)
  ^~~~~~~~
/usr/include/c++/7/functional:547:2: note:   template argument deduction/substitution failed:
/usr/include/c++/7/functional:558:2: note: candidate: template<class ... _Args, class _Result> _Result std::_Bind<_Functor(_Bound_args ...)>::operator()(_Args&& ...) const [with _Args = {_Args ...}; _Result = _Result; _Functor = void (ocb::ROS_TopicThread::*)(const boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > >&); _Bound_args = {std::reference_wrapper<std::shared_ptr<ocb::ROS_TopicThread> >, boost::arg<1>}]
  operator()(_Args&&... __args) const
  ^~~~~~~~
/usr/include/c++/7/functional:558:2: note:   template argument deduction/substitution failed:
/usr/include/c++/7/functional:576:2: note: candidate: template<class ... _Args, class _Result> _Result std::_Bind<_Functor(_Bound_args ...)>::operator()(_Args&& ...) volatile [with _Args = {_Args ...}; _Result = _Result; _Functor = void (ocb ...
(more)
edit retag flag offensive close merge delete

Comments

please post the full error message including some context.

mgruhler gravatar image mgruhler  ( 2021-06-21 03:50:16 -0600 )edit

@mgruhler Do let me know if there is any other info i can provide

gyrados10 gravatar image gyrados10  ( 2021-06-21 10:28:47 -0600 )edit