Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

not to use zero_allocate #1000

Conversation

iuhilnehc-ynos
Copy link
Collaborator

to fix the issue reported by valgrind, the zero_allocate of allocator passed by rclcpp can't be used.

log

==1067672== Mismatched free() / delete / delete []
==1067672==    at 0x4840FBF: operator delete(void*) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==1067672==    by 0x378613: __gnu_cxx::new_allocator<char>::deallocate(char*, unsigned long) (new_allocator.h:128)
==1067672==    by 0x371AC3: std::allocator_traits<std::allocator<char> >::deallocate(std::allocator<char>&, char*, unsigned long) (alloc_traits.h:469)
==1067672==    by 0x3AD161: void rclcpp::allocator::retyped_deallocate<char, std::allocator<char> >(void*, void*) (allocator_common.hpp:50)
==1067672==    by 0x567F113: rcl_subscription_fini (subscription.c:193)
==1067672==    by 0x53F81EE: rclcpp::SubscriptionBase::SubscriptionBase(rclcpp::node_interfaces::NodeBaseInterface*, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rcl_subscription_options_s const&, bool)::{lambda(rcl_subscription_s*)#1}::operator()(rcl_subscription_s*) const (subscription_base.cpp:53)
==1067672==    by 0x53FBBCB: std::_Sp_counted_deleter<rcl_subscription_s*, rclcpp::SubscriptionBase::SubscriptionBase(rclcpp::node_interfaces::NodeBaseInterface*, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rcl_subscription_options_s const&, bool)::{lambda(rcl_subscription_s*)#1}, std::allocator<void>, (__gnu_cxx::_Lock_policy)2>::_M_dispose() (shared_ptr_base.h:471)
==1067672==    by 0x36BA77: std::_Sp_counted_base<(__gnu_cxx::_Lock_policy)2>::_M_release() (shared_ptr_base.h:155)
==1067672==    by 0x364F7A: std::__shared_count<(__gnu_cxx::_Lock_policy)2>::~__shared_count() (shared_ptr_base.h:730)
==1067672==    by 0x3B3807: std::__shared_ptr<rcl_subscription_s, (__gnu_cxx::_Lock_policy)2>::~__shared_ptr() (shared_ptr_base.h:1169)
==1067672==    by 0x3B3827: std::shared_ptr<rcl_subscription_s>::~shared_ptr() (shared_ptr.h:103)
==1067672==    by 0x53F90E8: rclcpp::SubscriptionBase::~SubscriptionBase() (subscription_base.cpp:88)
==1067672==  Address 0xd631ba0 is 0 bytes inside a block of size 248 alloc'd
==1067672==    at 0x4841D99: calloc (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==1067672==    by 0x56E109F: __default_zero_allocate (allocator.c:62)
==1067672==    by 0x567E7E7: rcl_subscription_init (subscription.c:94)
==1067672==    by 0x53F890A: rclcpp::SubscriptionBase::SubscriptionBase(rclcpp::node_interfaces::NodeBaseInterface*, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rcl_subscription_options_s const&, bool) (subscription_base.cpp:67)
==1067672==    by 0x3B0BCA: rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >::Subscription(rclcpp::node_interfaces::NodeBaseInterface*, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> >, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > > >) (subscription.hpp:147)
==1067672==    by 0x3AEA0F: void __gnu_cxx::new_allocator<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > >::construct<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > > > const&>(rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >*, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > > > const&) (new_allocator.h:146)
==1067672==    by 0x3ABFA9: void std::allocator_traits<std::allocator<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > > >::construct<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > > > const&>(std::allocator<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > >&, rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >*, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > > > const&) (alloc_traits.h:483)
==1067672==    by 0x3A8AD6: std::_Sp_counted_ptr_inplace<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, std::allocator<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > >, (__gnu_cxx::_Lock_policy)2>::_Sp_counted_ptr_inplace<rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > > > const&>(std::allocator<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > >, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > > > const&) (shared_ptr_base.h:548)
==1067672==    by 0x3A4D5F: std::__shared_count<(__gnu_cxx::_Lock_policy)2>::__shared_count<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, std::allocator<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > >, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > > > const&>(rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >*&, std::_Sp_alloc_shared_tag<std::allocator<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > > >, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > > > const&) (shared_ptr_base.h:679)
==1067672==    by 0x3A14A5: std::__shared_ptr<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, (__gnu_cxx::_Lock_policy)2>::__shared_ptr<std::allocator<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > >, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > > > const&>(std::_Sp_alloc_shared_tag<std::allocator<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > > >, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > > > const&) (shared_ptr_base.h:1344)
==1067672==    by 0x39CC4F: std::shared_ptr<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > >::shared_ptr<std::allocator<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > >, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > > > const&>(std::_Sp_alloc_shared_tag<std::allocator<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > > >, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > > > const&) (shared_ptr.h:359)
==1067672==    by 0x396C1A: std::shared_ptr<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > > std::allocate_shared<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, std::allocator<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > >, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > > > const&>(std::allocator<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > > const&, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > > > const&) (shared_ptr.h:702)
==1067672== 

Signed-off-by: Chen Lihui lihui.chen@sony.com

Chen Lihui added 2 commits August 17, 2022 13:47
Signed-off-by: Chen Lihui <lihui.chen@sony.com>
Signed-off-by: Chen Lihui <lihui.chen@sony.com>
@clalancette
Copy link
Contributor

to fix the issue reported by valgrind, the zero_allocate of allocator passed by rclcpp can't be used.

Do you understand why valgrind is upset with it? As far as I understand, in the default implementation zero_allocate is just a call to calloc, so this should work. Also, there are many other places in the ROS 2 codebase that use zero_allocate, so if there is a problem we should probably fix it at the source rather than avoiding it.

@iuhilnehc-ynos
Copy link
Collaborator Author

Do you understand why valgrind is upset with it?

The memory allocated by calloc(c) should not be deleteed(c++). valgrind reported it as Mismatched.

https://github.com/ros2/rclcpp/blob/c769b1b03032d6789daa6d075cf63e955079953c/rclcpp/include/rclcpp/allocator/allocator_common.hpp#L73-L78

  rcl_allocator_t rcl_allocator = rcl_get_default_allocator();
#ifndef _WIN32
  rcl_allocator.allocate = &retyped_allocate<Alloc>;
  rcl_allocator.deallocate = &retyped_deallocate<T, Alloc>;
  rcl_allocator.reallocate = &retyped_reallocate<T, Alloc>;
  rcl_allocator.state = &allocator;

zero_allocate is not updated. Do you have any suggestions?

@iuhilnehc-ynos
Copy link
Collaborator Author

@clalancette

If you think ros2/rclcpp#1995 is acceptable, I'll close this PR.

@fujitatomoya
Copy link
Collaborator

@iuhilnehc-ynos @clalancette

i believe ros2/rclcpp#1995 makes more sense to address the root cause, delete on calloced memory makes valgrind unhappy cz it calls dtor on delete.

@clalancette
Copy link
Contributor

The memory allocated by calloc(c) should not be deleteed(c++). valgrind reported it as Mismatched.

Ah, I see. That makes much more sense. Thanks for the explanation.

i believe ros2/rclcpp#1995 makes more sense to address the root cause, delete on calloced memory makes valgrind unhappy cz it calls dtor on delete.

Yeah, agreed. I think that one makes more sense. @iuhilnehc-ynos I'll suggest closing this one out and we can concentrate on 1995.

@iuhilnehc-ynos
Copy link
Collaborator Author

Close it in favor of ros2/rclcpp#1995

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

3 participants