Skip to content

Member callback not working for GTest class with gcc7 #479

@dhood

Description

@dhood

In #343 we saw decltype cannot resolve address of overloaded function issues with gcc7. That prompted #346 which resolved it for the most part.

There seems to be a case that is not covered still, which has shown up in testing of the turtlebot demo (in particular, map_server) on Bionic (which has gcc7).

I narrowed it down to callbacks that have been bound to a member of a class inheriting from gtest's testing::Test, i.e. something like:

auto callback = std::bind(&TestSubscription::OnMessage, this, std::placeholders::_1);
auto sub = node->create_subscription<IntraProcessMessage>("topic", callback);

where this is a GTest object. (I doubt that this is unique to classes inheriting from Test, that's just the situation that's come up.)

I added a test for this in #480 which does not compile on gcc7 (while plain classes/classes inheriting from Node are fine).

@esteve does anything happen to come to mind about what might be different for the class inheriting from Test?

Full error output from the test


In file included from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/client.hpp:31:0,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/callback_group.hpp:23,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp:25,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/executor.hpp:31,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp:22,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/executors.hpp:21,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/rclcpp.hpp:142,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/test/test_subscription.cpp:21:
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/function_traits.hpp: In instantiation of ‘struct rclcpp::function_traits::function_traits<std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)> >’:
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/function_traits.hpp:143:8:   required from ‘struct rclcpp::function_traits::same_arguments<std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>, std::function<void(std::unique_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::default_delete<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > > >, const rmw_message_info_t&)> >’
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:147:17:   required by substitution of ‘template<class CallbackT, typename std::enable_if<rclcpp::function_traits::same_arguments<CallbackT, std::function<void(std::unique_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::default_delete<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > > >, const rmw_message_info_t&)> >::value, void>::type* <anonymous> > void rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >::set<CallbackT, <enumerator> >(CallbackT) [with CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>; typename std::enable_if<rclcpp::function_traits::same_arguments<CallbackT, std::function<void(std::unique_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::default_delete<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > > >, const rmw_message_info_t&)> >::value, void>::type* <anonymous> = <missing>]’
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/subscription_factory.hpp:80:3:   required from ‘rclcpp::SubscriptionFactory rclcpp::create_subscription_factory(CallbackT&&, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; Alloc = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]’
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/create_subscription.hpp:48:88:   required from ‘typename rclcpp::Subscription<MessageT, Alloc>::SharedPtr rclcpp::create_subscription(rclcpp::node_interfaces::NodeTopicsInterface*, const string&, CallbackT&&, const rmw_qos_profile_t&, rclcpp::callback_group::CallbackGroup::SharedPtr, bool, bool, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; AllocatorT = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; typename rclcpp::Subscription<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >; std::__cxx11::string = std::__cxx11::basic_string<char>; rmw_qos_profile_t = rmw_qos_profile_t; rclcpp::callback_group::CallbackGroup::SharedPtr = std::shared_ptr<rclcpp::callback_group::CallbackGroup>; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]’
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/node_impl.hpp:105:80:   required from ‘std::shared_ptr<SubscriptionT> rclcpp::Node::create_subscription(const string&, CallbackT&&, const rmw_qos_profile_t&, rclcpp::callback_group::CallbackGroup::SharedPtr, bool, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; Alloc = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; std::__cxx11::string = std::__cxx11::basic_string<char>; rmw_qos_profile_t = rmw_qos_profile_t; rclcpp::callback_group::CallbackGroup::SharedPtr = std::shared_ptr<rclcpp::callback_group::CallbackGroup>; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]’
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/test/test_subscription.cpp:127:80:   required from here
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/function_traits.hpp:52:83: error: decltype cannot resolve address of overloaded function
     typename function_traits<decltype( & FunctionT::operator())>::arguments>::type;
                                                                                   ^
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/function_traits.hpp:57:72: error: decltype cannot resolve address of overloaded function
   using argument_type = typename std::tuple_element<N, arguments>::type;
                                                                        ^
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/function_traits.hpp:59:96: error: decltype cannot resolve address of overloaded function
   using return_type = typename function_traits<decltype( & FunctionT::operator())>::return_type;
                                                                                                ^
In file included from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/node_interfaces/node_topics_interface.hpp:29:0,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/node.hpp:51,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/executors/single_threaded_executor.hpp:28,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/executors.hpp:22,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/rclcpp.hpp:142,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/test/test_subscription.cpp:21:
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/subscription_factory.hpp: In instantiation of ‘rclcpp::SubscriptionFactory rclcpp::create_subscription_factory(CallbackT&&, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; Alloc = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]’:
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/create_subscription.hpp:48:88:   required from ‘typename rclcpp::Subscription<MessageT, Alloc>::SharedPtr rclcpp::create_subscription(rclcpp::node_interfaces::NodeTopicsInterface*, const string&, CallbackT&&, const rmw_qos_profile_t&, rclcpp::callback_group::CallbackGroup::SharedPtr, bool, bool, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; AllocatorT = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; typename rclcpp::Subscription<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >; std::__cxx11::string = std::__cxx11::basic_string<char>; rmw_qos_profile_t = rmw_qos_profile_t; rclcpp::callback_group::CallbackGroup::SharedPtr = std::shared_ptr<rclcpp::callback_group::CallbackGroup>; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]’
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/node_impl.hpp:105:80:   required from ‘std::shared_ptr<SubscriptionT> rclcpp::Node::create_subscription(const string&, CallbackT&&, const rmw_qos_profile_t&, rclcpp::callback_group::CallbackGroup::SharedPtr, bool, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; Alloc = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; std::__cxx11::string = std::__cxx11::basic_string<char>; rmw_qos_profile_t = rmw_qos_profile_t; rclcpp::callback_group::CallbackGroup::SharedPtr = std::shared_ptr<rclcpp::callback_group::CallbackGroup>; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]’
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/test/test_subscription.cpp:127:80:   required from here
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/subscription_factory.hpp:80:3: error: no matching function for call to ‘rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >::set(std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&)’
   any_subscription_callback.set(std::forward<CallbackT>(callback));
   ^~~~~~~~~~~~~~~~~~~~~~~~~
In file included from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/subscription.hpp:35:0,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/callback_group.hpp:25,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp:25,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/executor.hpp:31,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/executors/multi_threaded_executor.hpp:22,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/executors.hpp:21,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/rclcpp.hpp:142,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/test/test_subscription.cpp:21:
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:79:8: note: candidate: template<class CallbackT, typename std::enable_if<rclcpp::function_traits::same_arguments<CallbackT, std::function<void(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)> >::value, void>::type* <anonymous> > void rclcpp::AnySubscriptionCallback<MessageT, Alloc>::set(CallbackT) [with CallbackT = CallbackT; typename std::enable_if<rclcpp::function_traits::same_arguments<CallbackT, std::function<void(std::shared_ptr<_Tp>)> >::value>::type* <anonymous> = <enumerator>; MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; Alloc = std::allocator<void>]
   void set(CallbackT callback)
        ^~~
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:79:8: note:   template argument deduction/substitution failed:
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:77:17: error: ‘value’ is not a member of ‘rclcpp::function_traits::same_arguments<std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>, std::function<void(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)> >’
     >::type * = nullptr
                 ^~~~~~~
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:77:17: note: invalid template non-type parameter
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:93:8: note: candidate: template<class CallbackT, typename std::enable_if<rclcpp::function_traits::same_arguments<CallbackT, std::function<void(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >, const rmw_message_info_t&)> >::value, void>::type* <anonymous> > void rclcpp::AnySubscriptionCallback<MessageT, Alloc>::set(CallbackT) [with CallbackT = CallbackT; typename std::enable_if<rclcpp::function_traits::same_arguments<CallbackT, std::function<void(std::shared_ptr<_Tp>, const rmw_message_info_t&)> >::value>::type* <anonymous> = <enumerator>; MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; Alloc = std::allocator<void>]
   void set(CallbackT callback)
        ^~~
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:93:8: note:   template argument deduction/substitution failed:
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:91:17: error: ‘value’ is not a member of ‘rclcpp::function_traits::same_arguments<std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>, std::function<void(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >, const rmw_message_info_t&)> >’
     >::type * = nullptr
                 ^~~~~~~
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:91:17: note: invalid template non-type parameter
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:107:8: note: candidate: template<class CallbackT, typename std::enable_if<rclcpp::function_traits::same_arguments<CallbackT, std::function<void(std::shared_ptr<const rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)> >::value, void>::type* <anonymous> > void rclcpp::AnySubscriptionCallback<MessageT, Alloc>::set(CallbackT) [with CallbackT = CallbackT; typename std::enable_if<rclcpp::function_traits::same_arguments<CallbackT, std::function<void(std::shared_ptr<const _Tp>)> >::value>::type* <anonymous> = <enumerator>; MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; Alloc = std::allocator<void>]
   void set(CallbackT callback)
        ^~~
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:107:8: note:   template argument deduction/substitution failed:
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:105:17: error: ‘value’ is not a member of ‘rclcpp::function_traits::same_arguments<std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>, std::function<void(std::shared_ptr<const rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)> >’
     >::type * = nullptr
                 ^~~~~~~
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:105:17: note: invalid template non-type parameter
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:121:8: note: candidate: template<class CallbackT, typename std::enable_if<rclcpp::function_traits::same_arguments<CallbackT, std::function<void(std::shared_ptr<const rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >, const rmw_message_info_t&)> >::value, void>::type* <anonymous> > void rclcpp::AnySubscriptionCallback<MessageT, Alloc>::set(CallbackT) [with CallbackT = CallbackT; typename std::enable_if<rclcpp::function_traits::same_arguments<CallbackT, std::function<void(std::shared_ptr<const _Tp>, const rmw_message_info_t&)> >::value>::type* <anonymous> = <enumerator>; MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; Alloc = std::allocator<void>]
   void set(CallbackT callback)
        ^~~
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:121:8: note:   template argument deduction/substitution failed:
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:119:17: error: ‘value’ is not a member of ‘rclcpp::function_traits::same_arguments<std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>, std::function<void(std::shared_ptr<const rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >, const rmw_message_info_t&)> >’
     >::type * = nullptr
                 ^~~~~~~
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:119:17: note: invalid template non-type parameter
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:135:8: note: candidate: template<class CallbackT, typename std::enable_if<rclcpp::function_traits::same_arguments<CallbackT, std::function<void(std::unique_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::default_delete<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > > >)> >::value, void>::type* <anonymous> > void rclcpp::AnySubscriptionCallback<MessageT, Alloc>::set(CallbackT) [with CallbackT = CallbackT; typename std::enable_if<rclcpp::function_traits::same_arguments<CallbackT, std::function<void(std::unique_ptr<MessageT, typename std::conditional<std::is_same<typename std::allocator_traits<typename std::allocator_traits<_Alloc>::rebind_traits<MessageT>::allocator_type>::rebind_alloc<MessageT>, typename std::allocator<void>::rebind<_Tp1>::other>::value, std::default_delete<_Tp>, rclcpp::allocator::AllocatorDeleter<typename std::allocator_traits<_Alloc>::rebind_traits<MessageT>::allocator_type> >::type>)> >::value>::type* <anonymous> = <enumerator>; MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; Alloc = std::allocator<void>]
   void set(CallbackT callback)
        ^~~
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:135:8: note:   template argument deduction/substitution failed:
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:133:17: error: ‘value’ is not a member of ‘rclcpp::function_traits::same_arguments<std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>, std::function<void(std::unique_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::default_delete<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > > >)> >’
     >::type * = nullptr
                 ^~~~~~~
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:133:17: note: invalid template non-type parameter
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:149:8: note: candidate: template<class CallbackT, typename std::enable_if<rclcpp::function_traits::same_arguments<CallbackT, std::function<void(std::unique_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::default_delete<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > > >, const rmw_message_info_t&)> >::value, void>::type* <anonymous> > void rclcpp::AnySubscriptionCallback<MessageT, Alloc>::set(CallbackT) [with CallbackT = CallbackT; typename std::enable_if<rclcpp::function_traits::same_arguments<CallbackT, std::function<void(std::unique_ptr<MessageT, typename std::conditional<std::is_same<typename std::allocator_traits<typename std::allocator_traits<_Alloc>::rebind_traits<MessageT>::allocator_type>::rebind_alloc<MessageT>, typename std::allocator<void>::rebind<_Tp1>::other>::value, std::default_delete<_Tp>, rclcpp::allocator::AllocatorDeleter<typename std::allocator_traits<_Alloc>::rebind_traits<MessageT>::allocator_type> >::type>, const rmw_message_info_t&)> >::value>::type* <anonymous> = <enumerator>; MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; Alloc = std::allocator<void>]
   void set(CallbackT callback)
        ^~~
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/any_subscription_callback.hpp:149:8: note:   substitution of deduced template arguments resulted in errors seen above
In file included from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/node_interfaces/node_topics_interface.hpp:29:0,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/node.hpp:51,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/executors/single_threaded_executor.hpp:28,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/executors.hpp:22,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/rclcpp.hpp:142,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/test/test_subscription.cpp:21:
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/subscription_factory.hpp:110:31: error: no match for ‘operator=’ (operand types are ‘rclcpp::SubscriptionFactory::SetupIntraProcessFunction {aka std::function<void(std::shared_ptr<rclcpp::intra_process_manager::IntraProcessManager>, std::shared_ptr<rclcpp::SubscriptionBase>, const rcl_subscription_options_t&)>}’ and ‘rclcpp::create_subscription_factory(CallbackT&&, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; Alloc = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]::<lambda(rclcpp::intra_process_manager::IntraProcessManager::SharedPtr, rclcpp::SubscriptionBase::SharedPtr, const rcl_subscription_options_t&)>’)
   factory.setup_intra_process =
In file included from /usr/include/c++/7/future:48:0,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/executors.hpp:18,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/rclcpp.hpp:142,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/test/test_subscription.cpp:21:
/usr/include/c++/7/bits/std_function.h:480:7: note: candidate: std::function<_Res(_ArgTypes ...)>& std::function<_Res(_ArgTypes ...)>::operator=(const std::function<_Res(_ArgTypes ...)>&) [with _Res = void; _ArgTypes = {std::shared_ptr<rclcpp::intra_process_manager::IntraProcessManager>, std::shared_ptr<rclcpp::SubscriptionBase>, const rcl_subscription_options_t&}]
       operator=(const function& __x)
       ^~~~~~~~
/usr/include/c++/7/bits/std_function.h:480:7: note:   no known conversion for argument 1 from ‘rclcpp::create_subscription_factory(CallbackT&&, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; Alloc = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]::<lambda(rclcpp::intra_process_manager::IntraProcessManager::SharedPtr, rclcpp::SubscriptionBase::SharedPtr, const rcl_subscription_options_t&)>’ to ‘const std::function<void(std::shared_ptr<rclcpp::intra_process_manager::IntraProcessManager>, std::shared_ptr<rclcpp::SubscriptionBase>, const rcl_subscription_options_t&)>&’
/usr/include/c++/7/bits/std_function.h:498:7: note: candidate: std::function<_Res(_ArgTypes ...)>& std::function<_Res(_ArgTypes ...)>::operator=(std::function<_Res(_ArgTypes ...)>&&) [with _Res = void; _ArgTypes = {std::shared_ptr<rclcpp::intra_process_manager::IntraProcessManager>, std::shared_ptr<rclcpp::SubscriptionBase>, const rcl_subscription_options_t&}]
       operator=(function&& __x) noexcept
       ^~~~~~~~
/usr/include/c++/7/bits/std_function.h:498:7: note:   no known conversion for argument 1 from ‘rclcpp::create_subscription_factory(CallbackT&&, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; Alloc = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]::<lambda(rclcpp::intra_process_manager::IntraProcessManager::SharedPtr, rclcpp::SubscriptionBase::SharedPtr, const rcl_subscription_options_t&)>’ to ‘std::function<void(std::shared_ptr<rclcpp::intra_process_manager::IntraProcessManager>, std::shared_ptr<rclcpp::SubscriptionBase>, const rcl_subscription_options_t&)>&&’
/usr/include/c++/7/bits/std_function.h:512:7: note: candidate: std::function<_Res(_ArgTypes ...)>& std::function<_Res(_ArgTypes ...)>::operator=(std::nullptr_t) [with _Res = void; _ArgTypes = {std::shared_ptr<rclcpp::intra_process_manager::IntraProcessManager>, std::shared_ptr<rclcpp::SubscriptionBase>, const rcl_subscription_options_t&}; std::nullptr_t = std::nullptr_t]
       operator=(nullptr_t) noexcept
       ^~~~~~~~
/usr/include/c++/7/bits/std_function.h:512:7: note:   no known conversion for argument 1 from ‘rclcpp::create_subscription_factory(CallbackT&&, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; Alloc = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]::<lambda(rclcpp::intra_process_manager::IntraProcessManager::SharedPtr, rclcpp::SubscriptionBase::SharedPtr, const rcl_subscription_options_t&)>’ to ‘std::nullptr_t’
/usr/include/c++/7/bits/std_function.h:541:2: note: candidate: template<class _Functor> std::function<_Res(_ArgTypes ...)>::_Requires<std::function<_Res(_ArgTypes ...)>::_Callable<typename std::decay<_U1>::type>, std::function<_Res(_ArgTypes ...)>&> std::function<_Res(_ArgTypes ...)>::operator=(_Functor&&) [with _Functor = _Functor; _Res = void; _ArgTypes = {std::shared_ptr<rclcpp::intra_process_manager::IntraProcessManager>, std::shared_ptr<rclcpp::SubscriptionBase>, const rcl_subscription_options_t&}]
  operator=(_Functor&& __f)
  ^~~~~~~~
/usr/include/c++/7/bits/std_function.h:541:2: note:   template argument deduction/substitution failed:
/usr/include/c++/7/bits/std_function.h: In substitution of ‘template<class _Functor> std::function<void(std::shared_ptr<rclcpp::intra_process_manager::IntraProcessManager>, std::shared_ptr<rclcpp::SubscriptionBase>, const rcl_subscription_options_t&)>::_Requires<std::function<void(std::shared_ptr<rclcpp::intra_process_manager::IntraProcessManager>, std::shared_ptr<rclcpp::SubscriptionBase>, const rcl_subscription_options_t&)>::_Callable<typename std::decay<_Tp>::type, typename std::result_of<typename std::decay<_Tp>::type&(std::shared_ptr<rclcpp::intra_process_manager::IntraProcessManager>, std::shared_ptr<rclcpp::SubscriptionBase>, const rcl_subscription_options_t&)>::type>, std::function<void(std::shared_ptr<rclcpp::intra_process_manager::IntraProcessManager>, std::shared_ptr<rclcpp::SubscriptionBase>, const rcl_subscription_options_t&)>&> std::function<void(std::shared_ptr<rclcpp::intra_process_manager::IntraProcessManager>, std::shared_ptr<rclcpp::SubscriptionBase>, const rcl_subscription_options_t&)>::operator=<_Functor>(_Functor&&) [with _Functor = rclcpp::create_subscription_factory(CallbackT&&, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; Alloc = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]::<lambda(rclcpp::intra_process_manager::IntraProcessManager::SharedPtr, rclcpp::SubscriptionBase::SharedPtr, const rcl_subscription_options_t&)>]’:
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/subscription_factory.hpp:110:31:   required from ‘rclcpp::SubscriptionFactory rclcpp::create_subscription_factory(CallbackT&&, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; Alloc = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]’
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/create_subscription.hpp:48:88:   required from ‘typename rclcpp::Subscription<MessageT, Alloc>::SharedPtr rclcpp::create_subscription(rclcpp::node_interfaces::NodeTopicsInterface*, const string&, CallbackT&&, const rmw_qos_profile_t&, rclcpp::callback_group::CallbackGroup::SharedPtr, bool, bool, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; AllocatorT = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; typename rclcpp::Subscription<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >; std::__cxx11::string = std::__cxx11::basic_string<char>; rmw_qos_profile_t = rmw_qos_profile_t; rclcpp::callback_group::CallbackGroup::SharedPtr = std::shared_ptr<rclcpp::callback_group::CallbackGroup>; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]’
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/node_impl.hpp:105:80:   required from ‘std::shared_ptr<SubscriptionT> rclcpp::Node::create_subscription(const string&, CallbackT&&, const rmw_qos_profile_t&, rclcpp::callback_group::CallbackGroup::SharedPtr, bool, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; Alloc = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; std::__cxx11::string = std::__cxx11::basic_string<char>; rmw_qos_profile_t = rmw_qos_profile_t; rclcpp::callback_group::CallbackGroup::SharedPtr = std::shared_ptr<rclcpp::callback_group::CallbackGroup>; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]’
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/test/test_subscription.cpp:127:80:   required from here
/usr/include/c++/7/bits/std_function.h:541:2: error: no type named ‘type’ in ‘class std::result_of<rclcpp::create_subscription_factory(CallbackT&&, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; Alloc = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]::<lambda(rclcpp::intra_process_manager::IntraProcessManager::SharedPtr, rclcpp::SubscriptionBase::SharedPtr, const rcl_subscription_options_t&)>&(std::shared_ptr<rclcpp::intra_process_manager::IntraProcessManager>, std::shared_ptr<rclcpp::SubscriptionBase>, const rcl_subscription_options_t&)>’
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/subscription_factory.hpp: In instantiation of ‘rclcpp::SubscriptionFactory rclcpp::create_subscription_factory(CallbackT&&, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; Alloc = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]’:
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/create_subscription.hpp:48:88:   required from ‘typename rclcpp::Subscription<MessageT, Alloc>::SharedPtr rclcpp::create_subscription(rclcpp::node_interfaces::NodeTopicsInterface*, const string&, CallbackT&&, const rmw_qos_profile_t&, rclcpp::callback_group::CallbackGroup::SharedPtr, bool, bool, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; AllocatorT = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; typename rclcpp::Subscription<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >; std::__cxx11::string = std::__cxx11::basic_string<char>; rmw_qos_profile_t = rmw_qos_profile_t; rclcpp::callback_group::CallbackGroup::SharedPtr = std::shared_ptr<rclcpp::callback_group::CallbackGroup>; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]’
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/node_impl.hpp:105:80:   required from ‘std::shared_ptr<SubscriptionT> rclcpp::Node::create_subscription(const string&, CallbackT&&, const rmw_qos_profile_t&, rclcpp::callback_group::CallbackGroup::SharedPtr, bool, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; Alloc = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; std::__cxx11::string = std::__cxx11::basic_string<char>; rmw_qos_profile_t = rmw_qos_profile_t; rclcpp::callback_group::CallbackGroup::SharedPtr = std::shared_ptr<rclcpp::callback_group::CallbackGroup>; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]’
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/test/test_subscription.cpp:127:80:   required from here
/usr/include/c++/7/bits/std_function.h:550:2: note: candidate: template<class _Functor> std::function<_Res(_ArgTypes ...)>& std::function<_Res(_ArgTypes ...)>::operator=(std::reference_wrapper<_Functor>) [with _Functor = _Functor; _Res = void; _ArgTypes = {std::shared_ptr<rclcpp::intra_process_manager::IntraProcessManager>, std::shared_ptr<rclcpp::SubscriptionBase>, const rcl_subscription_options_t&}]
  operator=(reference_wrapper<_Functor> __f) noexcept
  ^~~~~~~~
/usr/include/c++/7/bits/std_function.h:550:2: note:   template argument deduction/substitution failed:
In file included from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/node_interfaces/node_topics_interface.hpp:29:0,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/node.hpp:51,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/executors/single_threaded_executor.hpp:28,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/executors.hpp:22,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/rclcpp.hpp:142,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/test/test_subscription.cpp:21:
/home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/subscription_factory.hpp:110:31: note:   ‘rclcpp::create_subscription_factory(CallbackT&&, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; Alloc = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]::<lambda(rclcpp::intra_process_manager::IntraProcessManager::SharedPtr, rclcpp::SubscriptionBase::SharedPtr, const rcl_subscription_options_t&)>’ is not derived from ‘std::reference_wrapper<_Tp>’
   factory.setup_intra_process =
In file included from /usr/include/c++/7/future:48:0,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/executors.hpp:18,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/include/rclcpp/rclcpp.hpp:142,
                 from /home/dhood/ros2_ws/src/ros2/rclcpp/rclcpp/test/test_subscription.cpp:21:
/usr/include/c++/7/bits/std_function.h:541:2: error: ‘std::function<_Res(_ArgTypes ...)>::_Requires<std::function<_Res(_ArgTypes ...)>::_Callable<typename std::decay<_U1>::type>, std::function<_Res(_ArgTypes ...)>&> std::function<_Res(_ArgTypes ...)>::operator=(_Functor&&) [with _Functor = rclcpp::create_subscription_factory(CallbackT&&, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; Alloc = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]::<lambda(rclcpp::node_interfaces::NodeBaseInterface*, const string&, rcl_subscription_options_t&)>; _Res = std::shared_ptr<rclcpp::SubscriptionBase>; _ArgTypes = {rclcpp::node_interfaces::NodeBaseInterface*, const std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >&, rcl_subscription_options_t&}; std::function<_Res(_ArgTypes ...)>::_Requires<std::function<_Res(_ArgTypes ...)>::_Callable<typename std::decay<_U1>::type>, std::function<_Res(_ArgTypes ...)>&> = std::function<std::shared_ptr<rclcpp::SubscriptionBase>(rclcpp::node_interfaces::NodeBaseInterface*, const std::__cxx11::basic_string<char>&, rcl_subscription_options_t&)>&]’, declared using local type ‘rclcpp::create_subscription_factory(CallbackT&&, typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr, std::shared_ptr<PublisherT>) [with MessageT = rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >; CallbackT = std::_Bind<void (TestSubscription::*(TestSubscription_callback_bind_Test*, std::_Placeholder<1>))(std::shared_ptr<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> > >)>&; Alloc = std::allocator<void>; SubscriptionT = rclcpp::Subscription<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> >; typename rclcpp::message_memory_strategy::MessageMemoryStrategy<MessageT, Alloc>::SharedPtr = std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::IntraProcessMessage_<std::allocator<void> >, std::allocator<void> > >]::<lambda(rclcpp::node_interfaces::NodeBaseInterface*, const string&, rcl_subscription_options_t&)>’, is used but never defined [-fpermissive]
  operator=(_Functor&& __f)
  ^~~~~~~~
CMakeFiles/test_subscription.dir/build.make:62: recipe for target 'CMakeFiles/test_subscription.dir/test/test_subscription.cpp.o' failed
make[2]: *** [CMakeFiles/test_subscription.dir/test/test_subscription.cpp.o] Error 1
CMakeFiles/Makefile2:419: recipe for target 'CMakeFiles/test_subscription.dir/all' failed
make[1]: *** [CMakeFiles/test_subscription.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2

Metadata

Metadata

Assignees

No one assigned

    Labels

    bugSomething isn't workingin reviewWaiting for review (Kanban column)

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions