Skip to content

registerCallback failed! #157

@unter-dev

Description

@unter-dev

code:

class Sensor_subscriber : public rclcpp::Node
{
  public:
    Sensor_subscriber():Node("Sensor_subscriber")
    {
      message_filters::Subscriber<sensor_msgs::msg::Image> Back_img_sub(this,"/sensing/camera/back/image_raw",rmw_qos_profile_sensor_data);
      message_filters::Subscriber<sensor_msgs::msg::Image> Back_right_img_sub(this,"/sensing/camera/back_right/image_raw",rmw_qos_profile_sensor_data);
      message_filters::Subscriber<sensor_msgs::msg::Image> Back_left_img_sub(this,"/sensing/camera/back_left/image_raw",rmw_qos_profile_sensor_data);
      message_filters::Subscriber<sensor_msgs::msg::Image> Front_img_sub(this,"/sensing/camera/front/image_raw",rmw_qos_profile_sensor_data);
      message_filters::Subscriber<sensor_msgs::msg::Image> Front_right_img_sub(this,"/sensing/front_right/image_raw",rmw_qos_profile_sensor_data);
      message_filters::Subscriber<sensor_msgs::msg::Image> Front_left_img_sub(this,"/sensing/camera/front_left/image_raw",rmw_qos_profile_sensor_data);
      message_filters::TimeSynchronizer<sensor_msgs::msg::Image, sensor_msgs::msg::Image, sensor_msgs::msg::Image, sensor_msgs::msg::Image, sensor_msgs::msg::Image,sensor_msgs::msg::Image> sync(Back_img_sub, Back_right_img_sub, Back_left_img_sub, Front_img_sub,Front_right_img_sub,Front_left_img_sub, 10);
      sync.registerCallback(std::bind(&Sensor_subscriber::Sensor_CB,this,_1,_2,_3,_4,_5,_6));
    }

  private:
    void Sensor_CB(sensor_msgs::msg::Image::SharedPtr &img_back, sensor_msgs::msg::Image::SharedPtr &img_back_right,
                   sensor_msgs::msg::Image::SharedPtr &img_back_left, sensor_msgs::msg::Image::SharedPtr &img_front,
                   sensor_msgs::msg::Image::SharedPtr &img_front_right, sensor_msgs::msg::Image::SharedPtr &img_front_left)`

log:

Starting >>> auto_ware_test
--- stderr: auto_ware_test                             
In file included from /opt/ros/galactic/include/message_filters/synchronizer.h:47,
                 from /opt/ros/galactic/include/message_filters/time_synchronizer.h:41,
                 from /home/hobot/auto_ware_test/src/test.cpp:11:
/opt/ros/galactic/include/message_filters/signal9.h: In instantiation of ‘message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(C&) [with C = const std::_Bind<void (Sensor_subscriber::*(Sensor_subscriber*, boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>))(std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&)>; M0 = sensor_msgs::msg::Image_<std::allocator<void> >; M1 = sensor_msgs::msg::Image_<std::allocator<void> >; M2 = sensor_msgs::msg::Image_<std::allocator<void> >; M3 = sensor_msgs::msg::Image_<std::allocator<void> >; M4 = sensor_msgs::msg::Image_<std::allocator<void> >; M5 = sensor_msgs::msg::Image_<std::allocator<void> >; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’:
/opt/ros/galactic/include/message_filters/synchronizer.h:298:40:   required from ‘message_filters::Connection message_filters::Synchronizer<Policy>::registerCallback(const C&) [with C = std::_Bind<void (Sensor_subscriber::*(Sensor_subscriber*, boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>))(std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&)>; Policy = message_filters::sync_policies::ExactTime<sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType>]’
/home/hobot/auto_ware_test/src/test.cpp:31:92:   required from here
/opt/ros/galactic/include/message_filters/signal9.h:280:267: error: no matching function for call to ‘message_filters::Signal9<sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType>::addCallback<const M0ConstPtr&, const M1ConstPtr&, const M2ConstPtr&, const M3ConstPtr&, const M4ConstPtr&, const M5ConstPtr&, const M6ConstPtr&, const M7ConstPtr&, const M8ConstPtr&>(std::_Bind_helper<false, const std::_Bind<void (Sensor_subscriber::*(Sensor_subscriber*, boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>))(std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&)>&, const std::_Placeholder<1>&, const std::_Placeholder<2>&, const std::_Placeholder<3>&, const std::_Placeholder<4>&, const std::_Placeholder<5>&, const std::_Placeholder<6>&, const std::_Placeholder<7>&, const std::_Placeholder<8>&, const std::_Placeholder<9>&>::type)’
  280 |                      const M8ConstPtr&>(std::bind(callback, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, std::placeholders::_6, std::placeholders::_7, std::placeholders::_8, std::placeholders::_9));
      |                                                                                                                                                                                                                                                                           ^
In file included from /opt/ros/galactic/include/message_filters/synchronizer.h:47,
                 from /opt/ros/galactic/include/message_filters/time_synchronizer.h:41,
                 from /home/hobot/auto_ware_test/src/test.cpp:11:
/opt/ros/galactic/include/message_filters/signal9.h:170:14: note: candidate: ‘message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(const std::function<void(P0, P1, P2, P3, P4, P5, P6, P7, P8)>&) [with P0 = const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&; P1 = const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&; P2 = const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&; P3 = const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&; P4 = const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&; P5 = const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&; P6 = const std::shared_ptr<const message_filters::NullType>&; P7 = const std::shared_ptr<const message_filters::NullType>&; P8 = const std::shared_ptr<const message_filters::NullType>&; M0 = sensor_msgs::msg::Image_<std::allocator<void> >; M1 = sensor_msgs::msg::Image_<std::allocator<void> >; M2 = sensor_msgs::msg::Image_<std::allocator<void> >; M3 = sensor_msgs::msg::Image_<std::allocator<void> >; M4 = sensor_msgs::msg::Image_<std::allocator<void> >; M5 = sensor_msgs::msg::Image_<std::allocator<void> >; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’
  170 |   Connection addCallback(const std::function<void(P0, P1, P2, P3, P4, P5, P6, P7, P8)>& callback)
      |              ^~~~~~~~~~~
/opt/ros/galactic/include/message_filters/signal9.h:170:89: note:   no known conversion for argument 1 from ‘std::_Bind_helper<false, const std::_Bind<void (Sensor_subscriber::*(Sensor_subscriber*, boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>))(std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&)>&, const std::_Placeholder<1>&, const std::_Placeholder<2>&, const std::_Placeholder<3>&, const std::_Placeholder<4>&, const std::_Placeholder<5>&, const std::_Placeholder<6>&, const std::_Placeholder<7>&, const std::_Placeholder<8>&, const std::_Placeholder<9>&>::type’ {aka ‘std::_Bind<std::_Bind<void (Sensor_subscriber::*(Sensor_subscriber*, boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>))(std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&)>(std::_Placeholder<1>, std::_Placeholder<2>, std::_Placeholder<3>, std::_Placeholder<4>, std::_Placeholder<5>, std::_Placeholder<6>, std::_Placeholder<7>, std::_Placeholder<8>, std::_Placeholder<9>)>’} to ‘const std::function<void(const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&, const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&, const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&, const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&, const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&, const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&, const std::shared_ptr<const message_filters::NullType>&, const std::shared_ptr<const message_filters::NullType>&, const std::shared_ptr<const message_filters::NullType>&)>&’
  170 |   Connection addCallback(const std::function<void(P0, P1, P2, P3, P4, P5, P6, P7, P8)>& callback)
      |                          ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~^~~~~~~~
/opt/ros/galactic/include/message_filters/signal9.h:180:14: note: candidate: ‘template<class P0, class P1> message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(void (*)(P0, P1)) [with P0 = P0; P1 = P1; M0 = sensor_msgs::msg::Image_<std::allocator<void> >; M1 = sensor_msgs::msg::Image_<std::allocator<void> >; M2 = sensor_msgs::msg::Image_<std::allocator<void> >; M3 = sensor_msgs::msg::Image_<std::allocator<void> >; M4 = sensor_msgs::msg::Image_<std::allocator<void> >; M5 = sensor_msgs::msg::Image_<std::allocator<void> >; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’
  180 |   Connection addCallback(void(*callback)(P0, P1))
      |              ^~~~~~~~~~~
/opt/ros/galactic/include/message_filters/signal9.h:180:14: note:   template argument deduction/substitution failed:
In file included from /opt/ros/galactic/include/message_filters/synchronizer.h:47,
                 from /opt/ros/galactic/include/message_filters/time_synchronizer.h:41,
                 from /home/hobot/auto_ware_test/src/test.cpp:11:
/opt/ros/galactic/include/message_filters/signal9.h:280:267: error: wrong number of template arguments (9, should be 2)
  280 |                      const M8ConstPtr&>(std::bind(callback, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, std::placeholders::_6, std::placeholders::_7, std::placeholders::_8, std::placeholders::_9));
      |                                                                                                                                                                                                                                                                           ^
In file included from /opt/ros/galactic/include/message_filters/synchronizer.h:47,
                 from /opt/ros/galactic/include/message_filters/time_synchronizer.h:41,
                 from /home/hobot/auto_ware_test/src/test.cpp:11:
/opt/ros/galactic/include/message_filters/signal9.h:186:14: note: candidate: ‘template<class P0, class P1, class P2> message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(void (*)(P0, P1, P2)) [with P0 = P0; P1 = P1; P2 = P2; M0 = sensor_msgs::msg::Image_<std::allocator<void> >; M1 = sensor_msgs::msg::Image_<std::allocator<void> >; M2 = sensor_msgs::msg::Image_<std::allocator<void> >; M3 = sensor_msgs::msg::Image_<std::allocator<void> >; M4 = sensor_msgs::msg::Image_<std::allocator<void> >; M5 = sensor_msgs::msg::Image_<std::allocator<void> >; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’
  186 |   Connection addCallback(void(*callback)(P0, P1, P2))
      |              ^~~~~~~~~~~
/opt/ros/galactic/include/message_filters/signal9.h:186:14: note:   template argument deduction/substitution failed:
In file included from /opt/ros/galactic/include/message_filters/synchronizer.h:47,
                 from /opt/ros/galactic/include/message_filters/time_synchronizer.h:41,
                 from /home/hobot/auto_ware_test/src/test.cpp:11:
/opt/ros/galactic/include/message_filters/signal9.h:280:267: error: wrong number of template arguments (9, should be 3)
  280 |                      const M8ConstPtr&>(std::bind(callback, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, std::placeholders::_6, std::placeholders::_7, std::placeholders::_8, std::placeholders::_9));
      |                                                                                                                                                                                                                                                                           ^
In file included from /opt/ros/galactic/include/message_filters/synchronizer.h:47,
                 from /opt/ros/galactic/include/message_filters/time_synchronizer.h:41,
                 from /home/hobot/auto_ware_test/src/test.cpp:11:
/opt/ros/galactic/include/message_filters/signal9.h:192:14: note: candidate: ‘template<class P0, class P1, class P2, class P3> message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(void (*)(P0, P1, P2, P3)) [with P0 = P0; P1 = P1; P2 = P2; P3 = P3; M0 = sensor_msgs::msg::Image_<std::allocator<void> >; M1 = sensor_msgs::msg::Image_<std::allocator<void> >; M2 = sensor_msgs::msg::Image_<std::allocator<void> >; M3 = sensor_msgs::msg::Image_<std::allocator<void> >; M4 = sensor_msgs::msg::Image_<std::allocator<void> >; M5 = sensor_msgs::msg::Image_<std::allocator<void> >; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’
  192 |   Connection addCallback(void(*callback)(P0, P1, P2, P3))
      |              ^~~~~~~~~~~
/opt/ros/galactic/include/message_filters/signal9.h:192:14: note:   template argument deduction/substitution failed:
In file included from /opt/ros/galactic/include/message_filters/synchronizer.h:47,
                 from /opt/ros/galactic/include/message_filters/time_synchronizer.h:41,
                 from /home/hobot/auto_ware_test/src/test.cpp:11:
/opt/ros/galactic/include/message_filters/signal9.h:280:267: error: wrong number of template arguments (9, should be 4)
  280 |                      const M8ConstPtr&>(std::bind(callback, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, std::placeholders::_6, std::placeholders::_7, std::placeholders::_8, std::placeholders::_9));
      |                                                                                                                                                                                                                                                                           ^
In file included from /opt/ros/galactic/include/message_filters/synchronizer.h:47,
                 from /opt/ros/galactic/include/message_filters/time_synchronizer.h:41,
                 from /home/hobot/auto_ware_test/src/test.cpp:11:
/opt/ros/galactic/include/message_filters/signal9.h:198:14: note: candidate: ‘template<class P0, class P1, class P2, class P3, class P4> message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(void (*)(P0, P1, P2, P3, P4)) [with P0 = P0; P1 = P1; P2 = P2; P3 = P3; P4 = P4; M0 = sensor_msgs::msg::Image_<std::allocator<void> >; M1 = sensor_msgs::msg::Image_<std::allocator<void> >; M2 = sensor_msgs::msg::Image_<std::allocator<void> >; M3 = sensor_msgs::msg::Image_<std::allocator<void> >; M4 = sensor_msgs::msg::Image_<std::allocator<void> >; M5 = sensor_msgs::msg::Image_<std::allocator<void> >; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’
  198 |   Connection addCallback(void(*callback)(P0, P1, P2, P3, P4))
      |              ^~~~~~~~~~~
/opt/ros/galactic/include/message_filters/signal9.h:198:14: note:   template argument deduction/substitution failed:
In file included from /opt/ros/galactic/include/message_filters/synchronizer.h:47,
                 from /opt/ros/galactic/include/message_filters/time_synchronizer.h:41,
                 from /home/hobot/auto_ware_test/src/test.cpp:11:
/opt/ros/galactic/include/message_filters/signal9.h:280:267: error: wrong number of template arguments (9, should be 5)
  280 |                      const M8ConstPtr&>(std::bind(callback, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, std::placeholders::_6, std::placeholders::_7, std::placeholders::_8, std::placeholders::_9));
      |                                                                                                                                                                                                                                                                           ^
In file included from /opt/ros/galactic/include/message_filters/synchronizer.h:47,
                 from /opt/ros/galactic/include/message_filters/time_synchronizer.h:41,
                 from /home/hobot/auto_ware_test/src/test.cpp:11:
/opt/ros/galactic/include/message_filters/signal9.h:204:14: note: candidate: ‘template<class P0, class P1, class P2, class P3, class P4, class P5> message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(void (*)(P0, P1, P2, P3, P4, P5)) [with P0 = P0; P1 = P1; P2 = P2; P3 = P3; P4 = P4; P5 = P5; M0 = sensor_msgs::msg::Image_<std::allocator<void> >; M1 = sensor_msgs::msg::Image_<std::allocator<void> >; M2 = sensor_msgs::msg::Image_<std::allocator<void> >; M3 = sensor_msgs::msg::Image_<std::allocator<void> >; M4 = sensor_msgs::msg::Image_<std::allocator<void> >; M5 = sensor_msgs::msg::Image_<std::allocator<void> >; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’
  204 |   Connection addCallback(void(*callback)(P0, P1, P2, P3, P4, P5))
      |              ^~~~~~~~~~~
/opt/ros/galactic/include/message_filters/signal9.h:204:14: note:   template argument deduction/substitution failed:
In file included from /opt/ros/galactic/include/message_filters/synchronizer.h:47,
                 from /opt/ros/galactic/include/message_filters/time_synchronizer.h:41,
                 from /home/hobot/auto_ware_test/src/test.cpp:11:
/opt/ros/galactic/include/message_filters/signal9.h:280:267: error: wrong number of template arguments (9, should be 6)
  280 |                      const M8ConstPtr&>(std::bind(callback, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, std::placeholders::_6, std::placeholders::_7, std::placeholders::_8, std::placeholders::_9));
      |                                                                                                                                                                                                                                                                           ^
In file included from /opt/ros/galactic/include/message_filters/synchronizer.h:47,
                 from /opt/ros/galactic/include/message_filters/time_synchronizer.h:41,
                 from /home/hobot/auto_ware_test/src/test.cpp:11:
/opt/ros/galactic/include/message_filters/signal9.h:210:14: note: candidate: ‘template<class P0, class P1, class P2, class P3, class P4, class P5, class P6> message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(void (*)(P0, P1, P2, P3, P4, P5, P6)) [with P0 = P0; P1 = P1; P2 = P2; P3 = P3; P4 = P4; P5 = P5; P6 = P6; M0 = sensor_msgs::msg::Image_<std::allocator<void> >; M1 = sensor_msgs::msg::Image_<std::allocator<void> >; M2 = sensor_msgs::msg::Image_<std::allocator<void> >; M3 = sensor_msgs::msg::Image_<std::allocator<void> >; M4 = sensor_msgs::msg::Image_<std::allocator<void> >; M5 = sensor_msgs::msg::Image_<std::allocator<void> >; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’
  210 |   Connection addCallback(void(*callback)(P0, P1, P2, P3, P4, P5, P6))
      |              ^~~~~~~~~~~
/opt/ros/galactic/include/message_filters/signal9.h:210:14: note:   template argument deduction/substitution failed:
In file included from /opt/ros/galactic/include/message_filters/synchronizer.h:47,
                 from /opt/ros/galactic/include/message_filters/time_synchronizer.h:41,
                 from /home/hobot/auto_ware_test/src/test.cpp:11:
/opt/ros/galactic/include/message_filters/signal9.h:280:267: error: wrong number of template arguments (9, should be 7)
  280 |                      const M8ConstPtr&>(std::bind(callback, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, std::placeholders::_6, std::placeholders::_7, std::placeholders::_8, std::placeholders::_9));
      |                                                                                                                                                                                                                                                                           ^
/opt/ros/galactic/include/message_filters/signal9.h:216:14: note: candidate: ‘template<class P0, class P1, class P2, class P3, class P4, class P5, class P6, class P7> message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(void (*)(P0, P1, P2, P3, P4, P5, P6, P7)) [with P0 = P0; P1 = P1; P2 = P2; P3 = P3; P4 = P4; P5 = P5; P6 = P6; P7 = P7; M0 = sensor_msgs::msg::Image_<std::allocator<void> >; M1 = sensor_msgs::msg::Image_<std::allocator<void> >; M2 = sensor_msgs::msg::Image_<std::allocator<void> >; M3 = sensor_msgs::msg::Image_<std::allocator<void> >; M4 = sensor_msgs::msg::Image_<std::allocator<void> >; M5 = sensor_msgs::msg::Image_<std::allocator<void> >; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’
  216 |   Connection addCallback(void(*callback)(P0, P1, P2, P3, P4, P5, P6, P7))
      |              ^~~~~~~~~~~
/opt/ros/galactic/include/message_filters/signal9.h:216:14: note:   template argument deduction/substitution failed:
/opt/ros/galactic/include/message_filters/signal9.h:280:267: error: wrong number of template arguments (9, should be 8)
  280 |                      const M8ConstPtr&>(std::bind(callback, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, std::placeholders::_6, std::placeholders::_7, std::placeholders::_8, std::placeholders::_9));
      |                                                                                                                                                                                                                                                                           ^
/opt/ros/galactic/include/message_filters/signal9.h:222:14: note: candidate: ‘message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(void (*)(P0, P1, P2, P3, P4, P5, P6, P7, P8)) [with P0 = const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&; P1 = const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&; P2 = const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&; P3 = const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&; P4 = const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&; P5 = const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&; P6 = const std::shared_ptr<const message_filters::NullType>&; P7 = const std::shared_ptr<const message_filters::NullType>&; P8 = const std::shared_ptr<const message_filters::NullType>&; M0 = sensor_msgs::msg::Image_<std::allocator<void> >; M1 = sensor_msgs::msg::Image_<std::allocator<void> >; M2 = sensor_msgs::msg::Image_<std::allocator<void> >; M3 = sensor_msgs::msg::Image_<std::allocator<void> >; M4 = sensor_msgs::msg::Image_<std::allocator<void> >; M5 = sensor_msgs::msg::Image_<std::allocator<void> >; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’
  222 |   Connection addCallback(void(*callback)(P0, P1, P2, P3, P4, P5, P6, P7, P8))
      |              ^~~~~~~~~~~
/opt/ros/galactic/include/message_filters/signal9.h:222:32: note:   no known conversion for argument 1 from ‘std::_Bind_helper<false, const std::_Bind<void (Sensor_subscriber::*(Sensor_subscriber*, boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>))(std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&)>&, const std::_Placeholder<1>&, const std::_Placeholder<2>&, const std::_Placeholder<3>&, const std::_Placeholder<4>&, const std::_Placeholder<5>&, const std::_Placeholder<6>&, const std::_Placeholder<7>&, const std::_Placeholder<8>&, const std::_Placeholder<9>&>::type’ {aka ‘std::_Bind<std::_Bind<void (Sensor_subscriber::*(Sensor_subscriber*, boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>))(std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&)>(std::_Placeholder<1>, std::_Placeholder<2>, std::_Placeholder<3>, std::_Placeholder<4>, std::_Placeholder<5>, std::_Placeholder<6>, std::_Placeholder<7>, std::_Placeholder<8>, std::_Placeholder<9>)>’} to ‘void (*)(const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&, const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&, const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&, const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&, const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&, const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&, const std::shared_ptr<const message_filters::NullType>&, const std::shared_ptr<const message_filters::NullType>&, const std::shared_ptr<const message_filters::NullType>&)’
  222 |   Connection addCallback(void(*callback)(P0, P1, P2, P3, P4, P5, P6, P7, P8))
      |                          ~~~~~~^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
/opt/ros/galactic/include/message_filters/signal9.h:228:14: note: candidate: ‘template<class T, class P0, class P1> message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(void (T::*)(P0, P1), T*) [with T = T; P0 = P0; P1 = P1; M0 = sensor_msgs::msg::Image_<std::allocator<void> >; M1 = sensor_msgs::msg::Image_<std::allocator<void> >; M2 = sensor_msgs::msg::Image_<std::allocator<void> >; M3 = sensor_msgs::msg::Image_<std::allocator<void> >; M4 = sensor_msgs::msg::Image_<std::allocator<void> >; M5 = sensor_msgs::msg::Image_<std::allocator<void> >; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’
  228 |   Connection addCallback(void(T::*callback)(P0, P1), T* t)
      |              ^~~~~~~~~~~
/opt/ros/galactic/include/message_filters/signal9.h:228:14: note:   template argument deduction/substitution failed:
/opt/ros/galactic/include/message_filters/signal9.h:280:267: error: wrong number of template arguments (9, should be 3)
  280 |                      const M8ConstPtr&>(std::bind(callback, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, std::placeholders::_6, std::placeholders::_7, std::placeholders::_8, std::placeholders::_9));
      |                                                                                                                                                                                                                                                                           ^
/opt/ros/galactic/include/message_filters/signal9.h:234:14: note: candidate: ‘template<class T, class P0, class P1, class P2> message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(void (T::*)(P0, P1, P2), T*) [with T = T; P0 = P0; P1 = P1; P2 = P2; M0 = sensor_msgs::msg::Image_<std::allocator<void> >; M1 = sensor_msgs::msg::Image_<std::allocator<void> >; M2 = sensor_msgs::msg::Image_<std::allocator<void> >; M3 = sensor_msgs::msg::Image_<std::allocator<void> >; M4 = sensor_msgs::msg::Image_<std::allocator<void> >; M5 = sensor_msgs::msg::Image_<std::allocator<void> >; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’
  234 |   Connection addCallback(void(T::*callback)(P0, P1, P2), T* t)
      |              ^~~~~~~~~~~
/opt/ros/galactic/include/message_filters/signal9.h:234:14: note:   template argument deduction/substitution failed:
/opt/ros/galactic/include/message_filters/signal9.h:280:267: error: wrong number of template arguments (9, should be 4)
  280 |                      const M8ConstPtr&>(std::bind(callback, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, std::placeholders::_6, std::placeholders::_7, std::placeholders::_8, std::placeholders::_9));
      |                                                                                                                                                                                                                                                                           ^
/opt/ros/galactic/include/message_filters/signal9.h:240:14: note: candidate: ‘template<class T, class P0, class P1, class P2, class P3> message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(void (T::*)(P0, P1, P2, P3), T*) [with T = T; P0 = P0; P1 = P1; P2 = P2; P3 = P3; M0 = sensor_msgs::msg::Image_<std::allocator<void> >; M1 = sensor_msgs::msg::Image_<std::allocator<void> >; M2 = sensor_msgs::msg::Image_<std::allocator<void> >; M3 = sensor_msgs::msg::Image_<std::allocator<void> >; M4 = sensor_msgs::msg::Image_<std::allocator<void> >; M5 = sensor_msgs::msg::Image_<std::allocator<void> >; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’
  240 |   Connection addCallback(void(T::*callback)(P0, P1, P2, P3), T* t)
      |              ^~~~~~~~~~~
/opt/ros/galactic/include/message_filters/signal9.h:240:14: note:   template argument deduction/substitution failed:
/opt/ros/galactic/include/message_filters/signal9.h:280:267: error: wrong number of template arguments (9, should be 5)
  280 |                      const M8ConstPtr&>(std::bind(callback, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, std::placeholders::_6, std::placeholders::_7, std::placeholders::_8, std::placeholders::_9));
      |                                                                                                                                                                                                                                                                           ^
/opt/ros/galactic/include/message_filters/signal9.h:246:14: note: candidate: ‘template<class T, class P0, class P1, class P2, class P3, class P4> message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(void (T::*)(P0, P1, P2, P3, P4), T*) [with T = T; P0 = P0; P1 = P1; P2 = P2; P3 = P3; P4 = P4; M0 = sensor_msgs::msg::Image_<std::allocator<void> >; M1 = sensor_msgs::msg::Image_<std::allocator<void> >; M2 = sensor_msgs::msg::Image_<std::allocator<void> >; M3 = sensor_msgs::msg::Image_<std::allocator<void> >; M4 = sensor_msgs::msg::Image_<std::allocator<void> >; M5 = sensor_msgs::msg::Image_<std::allocator<void> >; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’
  246 |   Connection addCallback(void(T::*callback)(P0, P1, P2, P3, P4), T* t)
      |              ^~~~~~~~~~~
/opt/ros/galactic/include/message_filters/signal9.h:246:14: note:   template argument deduction/substitution failed:
/opt/ros/galactic/include/message_filters/signal9.h:280:267: error: wrong number of template arguments (9, should be 6)
  280 |                      const M8ConstPtr&>(std::bind(callback, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, std::placeholders::_6, std::placeholders::_7, std::placeholders::_8, std::placeholders::_9));
      |                                                                                                                                                                                                                                                                           ^
/opt/ros/galactic/include/message_filters/signal9.h:252:14: note: candidate: ‘template<class T, class P0, class P1, class P2, class P3, class P4, class P5> message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(void (T::*)(P0, P1, P2, P3, P4, P5), T*) [with T = T; P0 = P0; P1 = P1; P2 = P2; P3 = P3; P4 = P4; P5 = P5; M0 = sensor_msgs::msg::Image_<std::allocator<void> >; M1 = sensor_msgs::msg::Image_<std::allocator<void> >; M2 = sensor_msgs::msg::Image_<std::allocator<void> >; M3 = sensor_msgs::msg::Image_<std::allocator<void> >; M4 = sensor_msgs::msg::Image_<std::allocator<void> >; M5 = sensor_msgs::msg::Image_<std::allocator<void> >; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’
  252 |   Connection addCallback(void(T::*callback)(P0, P1, P2, P3, P4, P5), T* t)
      |              ^~~~~~~~~~~
/opt/ros/galactic/include/message_filters/signal9.h:252:14: note:   template argument deduction/substitution failed:
/opt/ros/galactic/include/message_filters/signal9.h:280:267: error: wrong number of template arguments (9, should be 7)
  280 |                      const M8ConstPtr&>(std::bind(callback, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, std::placeholders::_6, std::placeholders::_7, std::placeholders::_8, std::placeholders::_9));
      |                                                                                                                                                                                                                                                                           ^
/opt/ros/galactic/include/message_filters/signal9.h:258:14: note: candidate: ‘template<class T, class P0, class P1, class P2, class P3, class P4, class P5, class P6> message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(void (T::*)(P0, P1, P2, P3, P4, P5, P6), T*) [with T = T; P0 = P0; P1 = P1; P2 = P2; P3 = P3; P4 = P4; P5 = P5; P6 = P6; M0 = sensor_msgs::msg::Image_<std::allocator<void> >; M1 = sensor_msgs::msg::Image_<std::allocator<void> >; M2 = sensor_msgs::msg::Image_<std::allocator<void> >; M3 = sensor_msgs::msg::Image_<std::allocator<void> >; M4 = sensor_msgs::msg::Image_<std::allocator<void> >; M5 = sensor_msgs::msg::Image_<std::allocator<void> >; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’
  258 |   Connection addCallback(void(T::*callback)(P0, P1, P2, P3, P4, P5, P6), T* t)
      |              ^~~~~~~~~~~
/opt/ros/galactic/include/message_filters/signal9.h:258:14: note:   template argument deduction/substitution failed:
/opt/ros/galactic/include/message_filters/signal9.h:280:267: error: wrong number of template arguments (9, should be 8)
  280 |                      const M8ConstPtr&>(std::bind(callback, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, std::placeholders::_6, std::placeholders::_7, std::placeholders::_8, std::placeholders::_9));
      |                                                                                                                                                                                                                                                                           ^
/opt/ros/galactic/include/message_filters/signal9.h:264:14: note: candidate: ‘template<class T, class P0, class P1, class P2, class P3, class P4, class P5, class P6, class P7> message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(void (T::*)(P0, P1, P2, P3, P4, P5, P6, P7), T*) [with T = T; P0 = P0; P1 = P1; P2 = P2; P3 = P3; P4 = P4; P5 = P5; P6 = P6; P7 = P7; M0 = sensor_msgs::msg::Image_<std::allocator<void> >; M1 = sensor_msgs::msg::Image_<std::allocator<void> >; M2 = sensor_msgs::msg::Image_<std::allocator<void> >; M3 = sensor_msgs::msg::Image_<std::allocator<void> >; M4 = sensor_msgs::msg::Image_<std::allocator<void> >; M5 = sensor_msgs::msg::Image_<std::allocator<void> >; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’
  264 |   Connection addCallback(void(T::*callback)(P0, P1, P2, P3, P4, P5, P6, P7), T* t)
      |              ^~~~~~~~~~~
/opt/ros/galactic/include/message_filters/signal9.h:264:14: note:   template argument deduction/substitution failed:
/opt/ros/galactic/include/message_filters/signal9.h: In substitution of ‘template<class T, class P0, class P1, class P2, class P3, class P4, class P5, class P6, class P7> message_filters::Connection message_filters::Signal9<sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType>::addCallback<T, P0, P1, P2, P3, P4, P5, P6, P7>(void (T::*)(P0, P1, P2, P3, P4, P5, P6, P7), T*) [with T = const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&; P0 = const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&; P1 = const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&; P2 = const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&; P3 = const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&; P4 = const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&; P5 = const std::shared_ptr<const message_filters::NullType>&; P6 = const std::shared_ptr<const message_filters::NullType>&; P7 = const std::shared_ptr<const message_filters::NullType>&]’:
/opt/ros/galactic/include/message_filters/signal9.h:280:267:   required from ‘message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(C&) [with C = const std::_Bind<void (Sensor_subscriber::*(Sensor_subscriber*, boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>))(std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&)>; M0 = sensor_msgs::msg::Image_<std::allocator<void> >; M1 = sensor_msgs::msg::Image_<std::allocator<void> >; M2 = sensor_msgs::msg::Image_<std::allocator<void> >; M3 = sensor_msgs::msg::Image_<std::allocator<void> >; M4 = sensor_msgs::msg::Image_<std::allocator<void> >; M5 = sensor_msgs::msg::Image_<std::allocator<void> >; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’
/opt/ros/galactic/include/message_filters/synchronizer.h:298:40:   required from ‘message_filters::Connection message_filters::Synchronizer<Policy>::registerCallback(const C&) [with C = std::_Bind<void (Sensor_subscriber::*(Sensor_subscriber*, boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>))(std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&)>; Policy = message_filters::sync_policies::ExactTime<sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType>]’
/home/hobot/auto_ware_test/src/test.cpp:31:92:   required from here
/opt/ros/galactic/include/message_filters/signal9.h:264:14: error: forming pointer to reference type ‘const std::shared_ptr<const sensor_msgs::msg::Image_<std::allocator<void> > >&’
/opt/ros/galactic/include/message_filters/signal9.h: In instantiation of ‘message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(C&) [with C = const std::_Bind<void (Sensor_subscriber::*(Sensor_subscriber*, boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>))(std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&)>; M0 = sensor_msgs::msg::Image_<std::allocator<void> >; M1 = sensor_msgs::msg::Image_<std::allocator<void> >; M2 = sensor_msgs::msg::Image_<std::allocator<void> >; M3 = sensor_msgs::msg::Image_<std::allocator<void> >; M4 = sensor_msgs::msg::Image_<std::allocator<void> >; M5 = sensor_msgs::msg::Image_<std::allocator<void> >; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’:
/opt/ros/galactic/include/message_filters/synchronizer.h:298:40:   required from ‘message_filters::Connection message_filters::Synchronizer<Policy>::registerCallback(const C&) [with C = std::_Bind<void (Sensor_subscriber::*(Sensor_subscriber*, boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>))(std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&, std::shared_ptr<sensor_msgs::msg::Image_<std::allocator<void> > >&)>; Policy = message_filters::sync_policies::ExactTime<sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, sensor_msgs::msg::Image_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType>]’
/home/hobot/auto_ware_test/src/test.cpp:31:92:   required from here
/opt/ros/galactic/include/message_filters/signal9.h:270:14: note: candidate: ‘template<class C> message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(C&) [with C = C; M0 = sensor_msgs::msg::Image_<std::allocator<void> >; M1 = sensor_msgs::msg::Image_<std::allocator<void> >; M2 = sensor_msgs::msg::Image_<std::allocator<void> >; M3 = sensor_msgs::msg::Image_<std::allocator<void> >; M4 = sensor_msgs::msg::Image_<std::allocator<void> >; M5 = sensor_msgs::msg::Image_<std::allocator<void> >; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’
  270 |   Connection addCallback( C& callback)
      |              ^~~~~~~~~~~
/opt/ros/galactic/include/message_filters/signal9.h:270:14: note:   template argument deduction/substitution failed:
/opt/ros/galactic/include/message_filters/signal9.h:280:267: error: wrong number of template arguments (9, should be 1)
  280 |                      const M8ConstPtr&>(std::bind(callback, std::placeholders::_1, std::placeholders::_2, std::placeholders::_3, std::placeholders::_4, std::placeholders::_5, std::placeholders::_6, std::placeholders::_7, std::placeholders::_8, std::placeholders::_9));
      |                                                                                                                                                                                                                                                                           ^
make[2]: *** [CMakeFiles/test_1.dir/build.make:63:CMakeFiles/test_1.dir/src/test.cpp.o] 错误 1
make[1]: *** [CMakeFiles/Makefile2:78:CMakeFiles/test_1.dir/all] 错误 2
make: *** [Makefile:141:all] 错误 2
---
Failed   <<< auto_ware_test [7.91s, exited with code 2]

Summary: 0 packages finished [8.29s]
  1 package failed: auto_ware_test
  1 package had stderr output: auto_ware_test

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions