I was following a tutorial on message_filters in order to subscribe to 2 different topics of different type and later use it in a callback function. However, I got a weird long error message as follow:
In file included from /usr/include/boost/bind.hpp:22,
from /opt/ros/electric/stacks/ros_comm/clients/cpp/roscpp/include/ros/publisher.h:35,
from /opt/ros/electric/stacks/ros_comm/clients/cpp/roscpp/include/ros/node_handle.h:32,
from /opt/ros/electric/stacks/ros_comm/clients/cpp/roscpp/include/ros/ros.h:45,
from /home/shah/code/ros_workspace/point_cloud_drone/src/pointcloud_builder_node.cpp:1:
/usr/include/boost/bind/bind.hpp: In member function ‘void boost::_bi::list3<A1, A2, A3>::operator()(boost::_bi::type<void>, F&, A&, int) [with F = boost::_mfi::mf2<void, PointCloudBuilder, const geometry_msgs::PoseStampedConstPtr&, const geometry_msgs::Pose2DConstPtr&>, A = boost::_bi::list9<const boost::shared_ptr<const geometry_msgs::PoseStamped_<std::allocator<void> > >&, const boost::shared_ptr<const geometry_msgs::Pose2D_<std::allocator<void> > >&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&>, A1 = boost::arg<1>, A2 = boost::arg<2>, A3 = boost::_bi::value<PointCloudBuilder*>]’:
/usr/include/boost/bind/bind_template.hpp:305: instantiated from ‘typename boost::_bi::result_traits<R, F>::type boost::_bi::bind_t<R, F, L>::operator()(const A1&, const A2&, const A3&, const A4&, const A5&, const A6&, const A7&, const A8&, const A9&) [with A1 = boost::shared_ptr<const geometry_msgs::PoseStamped_<std::allocator<void> > >, A2 = boost::shared_ptr<const geometry_msgs::Pose2D_<std::allocator<void> > >, A3 = boost::shared_ptr<const message_filters::NullType>, A4 = boost::shared_ptr<const message_filters::NullType>, A5 = boost::shared_ptr<const message_filters::NullType>, A6 = boost::shared_ptr<const message_filters::NullType>, A7 = boost::shared_ptr<const message_filters::NullType>, A8 = boost::shared_ptr<const message_filters::NullType>, A9 = boost::shared_ptr<const message_filters::NullType>, R = void, F = boost::_mfi::mf2<void, PointCloudBuilder, const geometry_msgs::PoseStampedConstPtr&, const geometry_msgs::Pose2DConstPtr&>, L = boost::_bi::list3<boost::arg<1>, boost::arg<2>, boost::_bi::value<PointCloudBuilder*> >]’
/usr/include/boost/bind/bind.hpp:820: instantiated from ‘void boost::_bi::list9<A1, A2, A3, A4, A5, A6, A7, A8, A9>::operator()(boost::_bi::type<void>, F&, A&, int) [with F = boost::_bi::bind_t<void, boost::_mfi::mf2<void, PointCloudBuilder, const geometry_msgs::PoseStampedConstPtr&, const geometry_msgs::Pose2DConstPtr&>, boost::_bi::list3<boost::arg<1>, boost::arg<2>, boost::_bi::value<PointCloudBuilder*> > >, A = boost::_bi::list9<const boost::shared_ptr<const geometry_msgs::PoseStamped_<std::allocator<void> > >&, const boost::shared_ptr<const geometry_msgs::Pose2D_<std::allocator<void> > >&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&, const boost::shared_ptr<const message_filters::NullType>&>, A1 = boost::arg<1>, A2 = boost::arg<2>, A3 = boost::arg<3>, A4 = boost::arg<4>, A5 = boost::arg<5>, A6 = boost::arg<6>, A7 = boost::arg<7>, A8 = boost::arg<8>, A9 = boost::arg<9>]’
/usr/include/boost/bind/bind_template.hpp:305: instantiated from ‘typename boost::_bi::result_traits<R, F>::type boost::_bi::bind_t<R, F, L>::operator()(const A1&, const A2&, const A3&, const A4&, const A5&, const A6&, const A7&, const A8&, const A9&) [with A1 = boost::shared_ptr<const geometry_msgs::PoseStamped_<std::allocator<void> > >, A2 = boost::shared_ptr<const geometry_msgs::Pose2D_<std::allocator<void> > >, A3 = boost::shared_ptr<const message_filters::NullType>, A4 = boost::shared_ptr<const message_filters::NullType>, A5 = boost::shared_ptr<const message_filters::NullType>, A6 = boost::shared_ptr<const message_filters::NullType>, A7 = boost::shared_ptr<const message_filters::NullType>, A8 = boost::shared_ptr<const message_filters::NullType>, A9 = boost::shared_ptr<const message_filters::NullType>, R = boost::_bi::unspecified, F = boost::_bi::bind_t<void, boost::_mfi::mf2<void, PointCloudBuilder, const geometry_msgs::PoseStampedConstPtr&, const geometry_msgs::Pose2DConstPtr&>, boost::_bi::list3<boost::arg<1>, boost::arg<2>, boost::_bi::value<PointCloudBuilder*> > >, L = boost::_bi::list9<boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>, boost::arg<7>, boost::arg<8>, boost::arg<9> >]’
/usr/include/boost/function/function_template.hpp:153: instantiated from ‘static void boost::detail::function::void_function_obj_invoker9<FunctionObj, R, T0, T1, T2, T3, T4, T5, T6, T7, T8>::invoke(boost::detail::function::function_buffer&, T0, T1, T2, T3, T4, T5, T6, T7, T8) [with FunctionObj = boost::_bi::bind_t<boost::_bi::unspecified, boost::_bi::bind_t<void, boost::_mfi::mf2<void, PointCloudBuilder, const geometry_msgs::PoseStampedConstPtr&, const geometry_msgs::Pose2DConstPtr&>, boost::_bi::list3<boost::arg<1>, boost::arg<2>, boost::_bi::value<PointCloudBuilder*> > >, boost::_bi::list9<boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>, boost::arg<7>, boost::arg<8>, boost::arg<9> > >, R = void, T0 = const boost::shared_ptr<const geometry_msgs::PoseStamped_<std::allocator<void> > >&, T1 = const boost::shared_ptr<const geometry_msgs::Pose2D_<std::allocator<void> > >&, T2 = const boost::shared_ptr<const message_filters::NullType>&, T3 = const boost::shared_ptr<const message_filters::NullType>&, T4 = const boost::shared_ptr<const message_filters::NullType>&, T5 = const boost::shared_ptr<const message_filters::NullType>&, T6 = const boost::shared_ptr<const message_filters::NullType>&, T7 = const boost::shared_ptr<const message_filters::NullType>&, T8 = const boost::shared_ptr<const message_filters::NullType>&]’
/usr/include/boost/function/function_template.hpp:913: instantiated from ‘void boost::function9<R, T1, T2, T3, T4, T5, T6, T7, T8, T9>::assign_to(Functor) [with Functor = boost::_bi::bind_t<boost::_bi::unspecified, boost::_bi::bind_t<void, boost::_mfi::mf2<void, PointCloudBuilder, const geometry_msgs::PoseStampedConstPtr&, const geometry_msgs::Pose2DConstPtr&>, boost::_bi::list3<boost::arg<1>, boost::arg<2>, boost::_bi::value<PointCloudBuilder*> > >, boost::_bi::list9<boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>, boost::arg<7>, boost::arg<8>, boost::arg<9> > >, R = void, T0 = const boost::shared_ptr<const geometry_msgs::PoseStamped_<std::allocator<void> > >&, T1 = const boost::shared_ptr<const geometry_msgs::Pose2D_<std::allocator<void> > >&, T2 = const boost::shared_ptr<const message_filters::NullType>&, T3 = const boost::shared_ptr<const message_filters::NullType>&, T4 = const boost::shared_ptr<const message_filters::NullType>&, T5 = const boost::shared_ptr<const message_filters::NullType>&, T6 = const boost::shared_ptr<const message_filters::NullType>&, T7 = const boost::shared_ptr<const message_filters::NullType>&, T8 = const boost::shared_ptr<const message_filters::NullType>&]’
/usr/include/boost/function/function_template.hpp:722: instantiated from ‘boost::function9<R, T1, T2, T3, T4, T5, T6, T7, T8, T9>::function9(Functor, typename boost::enable_if_c<boost::type_traits::ice_not::value, int>::type) [with Functor = boost::_bi::bind_t<boost::_bi::unspecified, boost::_bi::bind_t<void, boost::_mfi::mf2<void, PointCloudBuilder, const geometry_msgs::PoseStampedConstPtr&, const geometry_msgs::Pose2DConstPtr&>, boost::_bi::list3<boost::arg<1>, boost::arg<2>, boost::_bi::value<PointCloudBuilder*> > >, boost::_bi::list9<boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>, boost::arg<7>, boost::arg<8>, boost::arg<9> > >, R = void, T0 = const boost::shared_ptr<const geometry_msgs::PoseStamped_<std::allocator<void> > >&, T1 = const boost::shared_ptr<const geometry_msgs::Pose2D_<std::allocator<void> > >&, T2 = const boost::shared_ptr<const message_filters::NullType>&, T3 = const boost::shared_ptr<const message_filters::NullType>&, T4 = const boost::shared_ptr<const message_filters::NullType>&, T5 = const boost::shared_ptr<const message_filters::NullType>&, T6 = const boost::shared_ptr<const message_filters::NullType>&, T7 = const boost::shared_ptr<const message_filters::NullType>&, T8 = const boost::shared_ptr<const message_filters::NullType>&]’
/usr/include/boost/function/function_template.hpp:1064: instantiated from ‘boost::function<R(T0, T1, T2, T3, T4, T5, T6, T7, T8)>::function(Functor, typename boost::enable_if_c<boost::type_traits::ice_not::value, int>::type) [with Functor = boost::_bi::bind_t<boost::_bi::unspecified, boost::_bi::bind_t<void, boost::_mfi::mf2<void, PointCloudBuilder, const geometry_msgs::PoseStampedConstPtr&, const geometry_msgs::Pose2DConstPtr&>, boost::_bi::list3<boost::arg<1>, boost::arg<2>, boost::_bi::value<PointCloudBuilder*> > >, boost::_bi::list9<boost::arg<1>, boost::arg<2>, boost::arg<3>, boost::arg<4>, boost::arg<5>, boost::arg<6>, boost::arg<7>, boost::arg<8>, boost::arg<9> > >, R = void, T0 = const boost::shared_ptr<const geometry_msgs::PoseStamped_<std::allocator<void> > >&, T1 = const boost::shared_ptr<const geometry_msgs::Pose2D_<std::allocator<void> > >&, T2 = const boost::shared_ptr<const message_filters::NullType>&, T3 = const boost::shared_ptr<const message_filters::NullType>&, T4 = const boost::shared_ptr<const message_filters::NullType>&, T5 = const boost::shared_ptr<const message_filters::NullType>&, T6 = const boost::shared_ptr<const message_filters::NullType>&, T7 = const boost::shared_ptr<const message_filters::NullType>&, T8 = const boost::shared_ptr<const message_filters::NullType>&]’
/opt/ros/electric/stacks/ros_comm/utilities/message_filters/include/message_filters/signal9.h:281: instantiated from ‘message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(C&) [with C = const boost::_bi::bind_t<void, boost::_mfi::mf2<void, PointCloudBuilder, const geometry_msgs::PoseStampedConstPtr&, const geometry_msgs::Pose2DConstPtr&>, boost::_bi::list3<boost::arg<1>, boost::arg<2>, boost::_bi::value<PointCloudBuilder*> > >, M0 = geometry_msgs::PoseStamped_<std::allocator<void> >, M1 = geometry_msgs::Pose2D_<std::allocator<void> >, M2 = message_filters::NullType, M3 = message_filters::NullType, M4 = message_filters::NullType, M5 = message_filters::NullType, M6 = message_filters::NullType, M7 = message_filters::NullType, M8 = message_filters::NullType]’
/opt/ros/electric/stacks/ros_comm/utilities/message_filters/include/message_filters/synchronizer.h:310: instantiated from ‘message_filters::Connection message_filters::Synchronizer<Policy>::registerCallback(const C&) [with C = boost::_bi::bind_t<void, boost::_mfi::mf2<void, PointCloudBuilder, const geometry_msgs::PoseStampedConstPtr&, const geometry_msgs::Pose2DConstPtr&>, boost::_bi::list3<boost::arg<1>, boost::arg<2>, boost::_bi::value<PointCloudBuilder*> > >, Policy = message_filters::sync_policies::ExactTime<geometry_msgs::PoseStamped_<std::allocator<void> >, geometry_msgs::Pose2D_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType>]’
/home/shah/code/ros_workspace/point_cloud_drone/src/pointcloud_builder_node.cpp:137: instantiated from here
/usr/include/boost/bind/bind.hpp:385: error: no match for call to ‘(boost::_mfi::mf2<void, PointCloudBuilder, const geometry_msgs::PoseStampedConstPtr&, const geometry_msgs::Pose2DConstPtr&>) (const boost::shared_ptr<const geometry_msgs::PoseStamped_<std::allocator<void> > >&, const boost::shared_ptr<const geometry_msgs::Pose2D_<std::allocator<void> > >&, PointCloudBuilder*&)’
/usr/include/boost/bind/mem_fn_template.hpp:272: note: candidates are: R boost::_mfi::mf2<R, T, A1, A2>::operator()(T*, A1, A2) const [with R = void, T = PointCloudBuilder, A1 = const geometry_msgs::PoseStampedConstPtr&, A2 = const geometry_msgs::Pose2DConstPtr&]
/usr/include/boost/bind/mem_fn_template.hpp:291: note: R boost::_mfi::mf2<R, T, A1, A2>::operator()(T&, A1, A2) const [with R = void, T = PointCloudBuilder, A1 = const geometry_msgs::PoseStampedConstPtr&, A2 = const geometry_msgs::Pose2DConstPtr&]
In file included from /opt/ros/electric/stacks/ros_comm/utilities/message_filters/include/message_filters/time_synchronizer.h:39,
from /home/shah/code/ros_workspace/point_cloud_drone/src/pointcloud_builder_node.cpp:20:
/opt/ros/electric/stacks/ros_comm/utilities/message_filters/include/message_filters/sync_policies/exact_time.h: In member function ‘void message_filters::sync_policies::ExactTime<M0, M1, M2, M3, M4, M5, M6, M7, M8>::add(const typename boost::mpl::at_c<typename message_filters::PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>::Events, i>::type&) [with int i = 1, M0 = geometry_msgs::PoseStamped_<std::allocator<void> >, M1 = geometry_msgs::Pose2D_<std::allocator<void> >, M2 = message_filters::NullType, M3 = message_filters::NullType, M4 = message_filters::NullType, M5 = message_filters::NullType, M6 = message_filters::NullType, M7 = message_filters::NullType, M8 = message_filters::NullType]’:
/opt/ros/electric/stacks/ros_comm/utilities/message_filters/include/message_filters/synchronizer.h:358: instantiated from ‘void message_filters::Synchronizer<Policy>::cb(const typename boost::mpl::at_c<typename Policy::Events, i>::type&) [with int i = 1, Policy = message_filters::sync_policies::ExactTime<geometry_msgs::PoseStamped_<std::allocator<void> >, geometry_msgs::Pose2D_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType>]’
/opt/ros/electric/stacks/ros_comm/utilities/message_filters/include/message_filters/synchronizer.h:291: instantiated from ‘void message_filters::Synchronizer<Policy>::connectInput(F0&, F1&, F2&, F3&, F4&, F5&, F6&, F7&, F8&) [with F0 = message_filters::Subscriber<geometry_msgs::PoseStamped_<std::allocator<void> > >, F1 = message_filters::Subscriber<geometry_msgs::Pose2D_<std::allocator<void> > >, F2 = message_filters::NullFilter<message_filters::NullType>, F3 = message_filters::NullFilter<message_filters::NullType>, F4 = message_filters::NullFilter<message_filters::NullType>, F5 = message_filters::NullFilter<message_filters::NullType>, F6 = message_filters::NullFilter<message_filters::NullType>, F7 = message_filters::NullFilter<message_filters::NullType>, F8 = message_filters::NullFilter<message_filters::NullType>, Policy = message_filters::sync_policies::ExactTime<geometry_msgs::PoseStamped_<std::allocator<void> >, geometry_msgs::Pose2D_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType>]’
/opt/ros/electric/stacks/ros_comm/utilities/message_filters/include/message_filters/synchronizer.h:282: instantiated from ‘void message_filters::Synchronizer<Policy>::connectInput(F0&, F1&, F2&, F3&, F4&, F5&, F6&, F7&) [with F0 = message_filters::Subscriber<geometry_msgs::PoseStamped_<std::allocator<void> > >, F1 = message_filters::Subscriber<geometry_msgs::Pose2D_<std::allocator<void> > >, F2 = message_filters::NullFilter<message_filters::NullType>, F3 = message_filters::NullFilter<message_filters::NullType>, F4 = message_filters::NullFilter<message_filters::NullType>, F5 = message_filters::NullFilter<message_filters::NullType>, F6 = message_filters::NullFilter<message_filters::NullType>, F7 = message_filters::NullFilter<message_filters::NullType>, Policy = message_filters::sync_policies::ExactTime<geometry_msgs::PoseStamped_<std::allocator<void> >, geometry_msgs::Pose2D_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType>]’
/opt/ros/electric/stacks/ros_comm/utilities/message_filters/include/message_filters/synchronizer.h:275: instantiated from ‘void message_filters::Synchronizer<Policy>::connectInput(F0&, F1&, F2&, F3&, F4&, F5&, F6&) [with F0 = message_filters::Subscriber<geometry_msgs::PoseStamped_<std::allocator<void> > >, F1 = message_filters::Subscriber<geometry_msgs::Pose2D_<std::allocator<void> > >, F2 = message_filters::NullFilter<message_filters::NullType>, F3 = message_filters::NullFilter<message_filters::NullType>, F4 = message_filters::NullFilter<message_filters::NullType>, F5 = message_filters::NullFilter<message_filters::NullType>, F6 = message_filters::NullFilter<message_filters::NullType>, Policy = message_filters::sync_policies::ExactTime<geometry_msgs::PoseStamped_<std::allocator<void> >, geometry_msgs::Pose2D_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType>]’
/opt/ros/electric/stacks/ros_comm/utilities/message_filters/include/message_filters/synchronizer.h:268: instantiated from ‘void message_filters::Synchronizer<Policy>::connectInput(F0&, F1&, F2&, F3&, F4&, F5&) [with F0 = message_filters::Subscriber<geometry_msgs::PoseStamped_<std::allocator<void> > >, F1 = message_filters::Subscriber<geometry_msgs::Pose2D_<std::allocator<void> > >, F2 = message_filters::NullFilter<message_filters::NullType>, F3 = message_filters::NullFilter<message_filters::NullType>, F4 = message_filters::NullFilter<message_filters::NullType>, F5 = message_filters::NullFilter<message_filters::NullType>, Policy = message_filters::sync_policies::ExactTime<geometry_msgs::PoseStamped_<std::allocator<void> >, geometry_msgs::Pose2D_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType>]’
/opt/ros/electric/stacks/ros_comm/utilities/message_filters/include/message_filters/synchronizer.h:261: instantiated from ‘void message_filters::Synchronizer<Policy>::connectInput(F0&, F1&, F2&, F3&, F4&) [with F0 = message_filters::Subscriber<geometry_msgs::PoseStamped_<std::allocator<void> > >, F1 = message_filters::Subscriber<geometry_msgs::Pose2D_<std::allocator<void> > >, F2 = message_filters::NullFilter<message_filters::NullType>, F3 = message_filters::NullFilter<message_filters::NullType>, F4 = message_filters::NullFilter<message_filters::NullType>, Policy = message_filters::sync_policies::ExactTime<geometry_msgs::PoseStamped_<std::allocator<void> >, geometry_msgs::Pose2D_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType>]’
/opt/ros/electric/stacks/ros_comm/utilities/message_filters/include/message_filters/synchronizer.h:254: instantiated from ‘void message_filters::Synchronizer<Policy>::connectInput(F0&, F1&, F2&, F3&) [with F0 = message_filters::Subscriber<geometry_msgs::PoseStamped_<std::allocator<void> > >, F1 = message_filters::Subscriber<geometry_msgs::Pose2D_<std::allocator<void> > >, F2 = message_filters::NullFilter<message_filters::NullType>, F3 = message_filters::NullFilter<message_filters::NullType>, Policy = message_filters::sync_policies::ExactTime<geometry_msgs::PoseStamped_<std::allocator<void> >, geometry_msgs::Pose2D_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType>]’
/opt/ros/electric/stacks/ros_comm/utilities/message_filters/include/message_filters/synchronizer.h:247: instantiated from ‘void message_filters::Synchronizer<Policy>::connectInput(F0&, F1&, F2&) [with F0 = message_filters::Subscriber<geometry_msgs::PoseStamped_<std::allocator<void> > >, F1 = message_filters::Subscriber<geometry_msgs::Pose2D_<std::allocator<void> > >, F2 = message_filters::NullFilter<message_filters::NullType>, Policy = message_filters::sync_policies::ExactTime<geometry_msgs::PoseStamped_<std::allocator<void> >, geometry_msgs::Pose2D_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType>]’
/opt/ros/electric/stacks/ros_comm/utilities/message_filters/include/message_filters/synchronizer.h:240: instantiated from ‘void message_filters::Synchronizer<Policy>::connectInput(F0&, F1&) [with F0 = message_filters::Subscriber<geometry_msgs::PoseStamped_<std::allocator<void> > >, F1 = message_filters::Subscriber<geometry_msgs::Pose2D_<std::allocator<void> > >, Policy = message_filters::sync_policies::ExactTime<geometry_msgs::PoseStamped_<std::allocator<void> >, geometry_msgs::Pose2D_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType>]’
My code snippet is like this:
message_filters::Subscriber<geometry_msgs::PoseStamped> poseLD_sub(n, "pose3D_LD", 1);
message_filters::Subscriber<geometry_msgs::Pose2D> pose2D_sub(n, "pose2D", 1);
TimeSynchronizer<geometry_msgs::PoseStamped, geometry_msgs::Pose2D> sync(poseLD_sub, pose2D_sub, 10);
sync.registerCallback(boost::bind(&PointCloudBuilder::callback, _1, _2, this));
And here is the callback function:
void PointCloudBuilder::callback(const geometry_msgs::PoseStampedConstPtr& poseLD_ptr, const geometry_msgs::Pose2DConstPtr& pose2D_ptr)
{
ROS_INFO("Here, I will process something on the arrived values");
}
Could someone check the parameter values that I filled, possibly wrong somewhere. From the error message, it could also be something to do with boost. What could go wrong here?
Originally posted by alfa_80 on ROS Answers with karma: 1053 on 2011-12-22
Post score: 1