ros2_rust
ros2_rust copied to clipboard
Fix memory leaks
Recently I've run lib unit tests with valgrind for my PR purposes and I've come across some memory leaks in rclrs lib. Here is full report:
==5444==
==5444== HEAP SUMMARY:
==5444== in use at exit: 43,376 bytes in 77 blocks
==5444== total heap usage: 86,438 allocs, 86,361 frees, 22,290,504 bytes allocated
==5444==
==5444== 64 bytes in 1 blocks are still reachable in loss record 1 of 20
==5444== at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==5444== by 0x70B8C26: rosidl_message_type_support_t const* rosidl_typesupport_cpp::get_typesupport_handle_function<rosidl_message_type_support_t>(rosidl_message_type_support_t const*, char const*) (in /opt/ros/foxy/lib/librosidl_typesupport_cpp.so)
==5444== by 0x63DA8E1: ??? (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x63D8F4D: ??? (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x63D960F: ??? (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x63E37CB: rmw_create_node (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x48649C7: rcl_node_init (in /opt/ros/foxy/lib/librcl.so)
==5444== by 0x141245: rclrs::node::builder::NodeBuilder::build (builder.rs:257)
==5444== by 0x1665EB: rclrs::create_node (lib.rs:97)
==5444== by 0x1586A9: rclrs::node::subscription::tests::test_instantiate_subscriber (subscription.rs:219)
==5444== by 0x15EED0: rclrs::node::subscription::tests::test_instantiate_subscriber::{{closure}} (subscription.rs:216)
==5444== by 0x13C40D: core::ops::function::FnOnce::call_once (function.rs:227)
==5444==
==5444== 64 bytes in 1 blocks are still reachable in loss record 2 of 20
==5444== at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==5444== by 0x4D19A61: rosidl_message_type_support_t const* rosidl_typesupport_c::get_typesupport_handle_function<rosidl_message_type_support_t>(rosidl_message_type_support_t const*, char const*) (in /opt/ros/foxy/lib/librosidl_typesupport_c.so)
==5444== by 0x63EAE77: ??? (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x63E9DE1: rmw_create_subscription (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x486B3FE: rcl_subscription_init (in /opt/ros/foxy/lib/librcl.so)
==5444== by 0x148800: rclrs::node::subscription::Subscription<T>::new (subscription.rs:106)
==5444== by 0x16544A: rclrs::node::Node::create_subscription (node.rs:206)
==5444== by 0x168360: rclrs::node::tests::test_create_subscription (node.rs:309)
==5444== by 0x1335E0: rclrs::node::tests::test_create_subscription::{{closure}} (node.rs:305)
==5444== by 0x13C4ED: core::ops::function::FnOnce::call_once (function.rs:227)
==5444== by 0x1A8302: call_once<fn(), ()> (function.rs:227)
==5444== by 0x1A8302: test::__rust_begin_short_backtrace (lib.rs:574)
==5444== by 0x1A7068: call_once<(), (dyn core::ops::function::FnOnce<(), Output=()> + core::marker::Send), alloc::alloc::Global> (boxed.rs:1861)
==5444== by 0x1A7068: call_once<(), alloc::boxed::Box<(dyn core::ops::function::FnOnce<(), Output=()> + core::marker::Send), alloc::alloc::Global>> (unwind_safe.rs:271)
==5444== by 0x1A7068: do_call<core::panic::unwind_safe::AssertUnwindSafe<alloc::boxed::Box<(dyn core::ops::function::FnOnce<(), Output=()> + core::marker::Send), alloc::alloc::Global>>, ()> (panicking.rs:492)
==5444== by 0x1A7068: try<(), core::panic::unwind_safe::AssertUnwindSafe<alloc::boxed::Box<(dyn core::ops::function::FnOnce<(), Output=()> + core::marker::Send), alloc::alloc::Global>>> (panicking.rs:456)
==5444== by 0x1A7068: catch_unwind<core::panic::unwind_safe::AssertUnwindSafe<alloc::boxed::Box<(dyn core::ops::function::FnOnce<(), Output=()> + core::marker::Send), alloc::alloc::Global>>, ()> (panic.rs:137)
==5444== by 0x1A7068: run_test_in_process (lib.rs:597)
==5444== by 0x1A7068: test::run_test::run_test_inner::{{closure}} (lib.rs:491)
==5444==
==5444== 64 bytes in 1 blocks are still reachable in loss record 3 of 20
==5444== at 0x483B7F3: malloc (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==5444== by 0x489F37C: rcutils_strndup (in /opt/ros/foxy/lib/librcutils.so)
==5444== by 0x489E340: rcutils_load_shared_library (in /opt/ros/foxy/lib/librcutils.so)
==5444== by 0x4D24D34: rcpputils::SharedLibrary::SharedLibrary(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&) (in /opt/ros/foxy/lib/librcpputils.so)
==5444== by 0x4D19A6F: rosidl_message_type_support_t const* rosidl_typesupport_c::get_typesupport_handle_function<rosidl_message_type_support_t>(rosidl_message_type_support_t const*, char const*) (in /opt/ros/foxy/lib/librosidl_typesupport_c.so)
==5444== by 0x63EAE77: ??? (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x63E9DE1: rmw_create_subscription (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x486B3FE: rcl_subscription_init (in /opt/ros/foxy/lib/librcl.so)
==5444== by 0x148800: rclrs::node::subscription::Subscription<T>::new (subscription.rs:106)
==5444== by 0x16544A: rclrs::node::Node::create_subscription (node.rs:206)
==5444== by 0x168360: rclrs::node::tests::test_create_subscription (node.rs:309)
==5444== by 0x1335E0: rclrs::node::tests::test_create_subscription::{{closure}} (node.rs:305)
==5444==
==5444== 64 bytes in 1 blocks are still reachable in loss record 4 of 20
==5444== at 0x483B7F3: malloc (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==5444== by 0x401677C: resize_scopes (dl-open.c:282)
==5444== by 0x401677C: dl_open_worker (dl-open.c:693)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x4015609: _dl_open (dl-open.c:837)
==5444== by 0x4AB634B: dlopen_doit (dlopen.c:66)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x4C1B9F2: _dl_catch_error (dl-error-skeleton.c:227)
==5444== by 0x4AB6B58: _dlerror_run (dlerror.c:170)
==5444== by 0x4AB63D9: dlopen@@GLIBC_2.2.5 (dlopen.c:87)
==5444== by 0x489E35E: rcutils_load_shared_library (in /opt/ros/foxy/lib/librcutils.so)
==5444== by 0x4D24D34: rcpputils::SharedLibrary::SharedLibrary(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&) (in /opt/ros/foxy/lib/librcpputils.so)
==5444== by 0x4D19A6F: rosidl_message_type_support_t const* rosidl_typesupport_c::get_typesupport_handle_function<rosidl_message_type_support_t>(rosidl_message_type_support_t const*, char const*) (in /opt/ros/foxy/lib/librosidl_typesupport_c.so)
==5444==
==5444== 72 bytes in 1 blocks are still reachable in loss record 5 of 20
==5444== at 0x483B7F3: malloc (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==5444== by 0x489FFF2: rcutils_string_map_init (in /opt/ros/foxy/lib/librcutils.so)
==5444== by 0x489BF1A: rcutils_logging_initialize_with_allocator (in /opt/ros/foxy/lib/librcutils.so)
==5444== by 0x489C23C: rcutils_logging_initialize (in /opt/ros/foxy/lib/librcutils.so)
==5444== by 0x48602BC: rcl_init (in /opt/ros/foxy/lib/librcl.so)
==5444== by 0x1592CD: rclrs::context::Context::new (context.rs:89)
==5444== by 0x158669: rclrs::node::subscription::tests::test_instantiate_subscriber (subscription.rs:218)
==5444== by 0x15EED0: rclrs::node::subscription::tests::test_instantiate_subscriber::{{closure}} (subscription.rs:216)
==5444== by 0x13C40D: core::ops::function::FnOnce::call_once (function.rs:227)
==5444== by 0x1A8302: call_once<fn(), ()> (function.rs:227)
==5444== by 0x1A8302: test::__rust_begin_short_backtrace (lib.rs:574)
==5444== by 0x1A7068: call_once<(), (dyn core::ops::function::FnOnce<(), Output=()> + core::marker::Send), alloc::alloc::Global> (boxed.rs:1861)
==5444== by 0x1A7068: call_once<(), alloc::boxed::Box<(dyn core::ops::function::FnOnce<(), Output=()> + core::marker::Send), alloc::alloc::Global>> (unwind_safe.rs:271)
==5444== by 0x1A7068: do_call<core::panic::unwind_safe::AssertUnwindSafe<alloc::boxed::Box<(dyn core::ops::function::FnOnce<(), Output=()> + core::marker::Send), alloc::alloc::Global>>, ()> (panicking.rs:492)
==5444== by 0x1A7068: try<(), core::panic::unwind_safe::AssertUnwindSafe<alloc::boxed::Box<(dyn core::ops::function::FnOnce<(), Output=()> + core::marker::Send), alloc::alloc::Global>>> (panicking.rs:456)
==5444== by 0x1A7068: catch_unwind<core::panic::unwind_safe::AssertUnwindSafe<alloc::boxed::Box<(dyn core::ops::function::FnOnce<(), Output=()> + core::marker::Send), alloc::alloc::Global>>, ()> (panic.rs:137)
==5444== by 0x1A7068: run_test_in_process (lib.rs:597)
==5444== by 0x1A7068: test::run_test::run_test_inner::{{closure}} (lib.rs:491)
==5444== by 0x17321D: {closure#1} (lib.rs:518)
==5444== by 0x17321D: std::sys_common::backtrace::__rust_begin_short_backtrace (backtrace.rs:122)
==5444==
==5444== 72 bytes in 1 blocks are still reachable in loss record 6 of 20
==5444== at 0x483B7F3: malloc (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==5444== by 0x489F37C: rcutils_strndup (in /opt/ros/foxy/lib/librcutils.so)
==5444== by 0x489E340: rcutils_load_shared_library (in /opt/ros/foxy/lib/librcutils.so)
==5444== by 0x4D24D34: rcpputils::SharedLibrary::SharedLibrary(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&) (in /opt/ros/foxy/lib/librcpputils.so)
==5444== by 0x70B8C34: rosidl_message_type_support_t const* rosidl_typesupport_cpp::get_typesupport_handle_function<rosidl_message_type_support_t>(rosidl_message_type_support_t const*, char const*) (in /opt/ros/foxy/lib/librosidl_typesupport_cpp.so)
==5444== by 0x63DA8E1: ??? (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x63D8F4D: ??? (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x63D960F: ??? (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x63E37CB: rmw_create_node (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x48649C7: rcl_node_init (in /opt/ros/foxy/lib/librcl.so)
==5444== by 0x141245: rclrs::node::builder::NodeBuilder::build (builder.rs:257)
==5444== by 0x1665EB: rclrs::create_node (lib.rs:97)
==5444==
==5444== 88 bytes in 1 blocks are still reachable in loss record 7 of 20
==5444== at 0x483B7F3: malloc (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==5444== by 0x400CDCE: add_dependency (dl-lookup.c:754)
==5444== by 0x400CDCE: _dl_lookup_symbol_x (dl-lookup.c:935)
==5444== by 0x4011196: _dl_fixup (dl-runtime.c:112)
==5444== by 0x4018B7D: _dl_runtime_resolve_xsave (dl-trampoline.h:126)
==5444== by 0x1F065EDF: ???
==5444==
==5444== 136 (64 direct, 72 indirect) bytes in 1 blocks are definitely lost in loss record 8 of 20
==5444== at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==5444== by 0x70B8C26: rosidl_message_type_support_t const* rosidl_typesupport_cpp::get_typesupport_handle_function<rosidl_message_type_support_t>(rosidl_message_type_support_t const*, char const*) (in /opt/ros/foxy/lib/librosidl_typesupport_cpp.so)
==5444== by 0x63DA8E1: ??? (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x63D8F4D: ??? (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x63D960F: ??? (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x63E37CB: rmw_create_node (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x48649C7: rcl_node_init (in /opt/ros/foxy/lib/librcl.so)
==5444== by 0x141245: rclrs::node::builder::NodeBuilder::build (builder.rs:257)
==5444== by 0x1665EB: rclrs::create_node (lib.rs:97)
==5444== by 0x124D91: rclrs::node::publisher::tests::create_fixture (publisher.rs:176)
==5444== by 0x1250F5: rclrs::node::publisher::tests::test_publish_message (publisher.rs:191)
==5444== by 0x141E30: rclrs::node::publisher::tests::test_publish_message::{{closure}} (publisher.rs:190)
==5444==
==5444== 136 (64 direct, 72 indirect) bytes in 1 blocks are definitely lost in loss record 9 of 20
==5444== at 0x483BE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==5444== by 0x70B8C26: rosidl_message_type_support_t const* rosidl_typesupport_cpp::get_typesupport_handle_function<rosidl_message_type_support_t>(rosidl_message_type_support_t const*, char const*) (in /opt/ros/foxy/lib/librosidl_typesupport_cpp.so)
==5444== by 0x63DA8E1: ??? (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x63D8F4D: ??? (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x63D960F: ??? (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x63E37CB: rmw_create_node (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x48649C7: rcl_node_init (in /opt/ros/foxy/lib/librcl.so)
==5444== by 0x141245: rclrs::node::builder::NodeBuilder::build (builder.rs:257)
==5444== by 0x1665EB: rclrs::create_node (lib.rs:97)
==5444== by 0x168209: rclrs::node::tests::test_create_subscription (node.rs:308)
==5444== by 0x1335E0: rclrs::node::tests::test_create_subscription::{{closure}} (node.rs:305)
==5444== by 0x13C4ED: core::ops::function::FnOnce::call_once (function.rs:227)
==5444==
==5444== 144 bytes in 2 blocks are indirectly lost in loss record 10 of 20
==5444== at 0x483B7F3: malloc (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==5444== by 0x489F37C: rcutils_strndup (in /opt/ros/foxy/lib/librcutils.so)
==5444== by 0x489E340: rcutils_load_shared_library (in /opt/ros/foxy/lib/librcutils.so)
==5444== by 0x4D24D34: rcpputils::SharedLibrary::SharedLibrary(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&) (in /opt/ros/foxy/lib/librcpputils.so)
==5444== by 0x70B8C34: rosidl_message_type_support_t const* rosidl_typesupport_cpp::get_typesupport_handle_function<rosidl_message_type_support_t>(rosidl_message_type_support_t const*, char const*) (in /opt/ros/foxy/lib/librosidl_typesupport_cpp.so)
==5444== by 0x63DA8E1: ??? (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x63D8F4D: ??? (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x63D960F: ??? (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x63E37CB: rmw_create_node (in /opt/ros/foxy/lib/librmw_fastrtps_cpp.so)
==5444== by 0x48649C7: rcl_node_init (in /opt/ros/foxy/lib/librcl.so)
==5444== by 0x141245: rclrs::node::builder::NodeBuilder::build (builder.rs:257)
==5444== by 0x1665EB: rclrs::create_node (lib.rs:97)
==5444==
==5444== 159 bytes in 4 blocks are still reachable in loss record 11 of 20
==5444== at 0x483B7F3: malloc (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==5444== by 0x401F5DE: strdup (strdup.c:42)
==5444== by 0x4019A91: _dl_load_cache_lookup (dl-cache.c:338)
==5444== by 0x400A989: _dl_map_object (dl-load.c:2102)
==5444== by 0x400F514: openaux (dl-deps.c:64)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x400F962: _dl_map_object_deps (dl-deps.c:248)
==5444== by 0x4015DAF: dl_open_worker (dl-open.c:571)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x4015609: _dl_open (dl-open.c:837)
==5444== by 0x4AB634B: dlopen_doit (dlopen.c:66)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444==
==5444== 176 bytes in 2 blocks are still reachable in loss record 12 of 20
==5444== at 0x483B7F3: malloc (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==5444== by 0x400CDCE: add_dependency (dl-lookup.c:754)
==5444== by 0x400CDCE: _dl_lookup_symbol_x (dl-lookup.c:935)
==5444== by 0x400DF23: elf_machine_rela (dl-machine.h:308)
==5444== by 0x400DF23: elf_dynamic_do_Rela (do-rel.h:137)
==5444== by 0x400DF23: _dl_relocate_object (dl-reloc.c:255)
==5444== by 0x4015F6B: dl_open_worker (dl-open.c:688)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x4015609: _dl_open (dl-open.c:837)
==5444== by 0x4AB634B: dlopen_doit (dlopen.c:66)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x4C1B9F2: _dl_catch_error (dl-error-skeleton.c:227)
==5444== by 0x4AB6B58: _dlerror_run (dlerror.c:170)
==5444== by 0x4AB63D9: dlopen@@GLIBC_2.2.5 (dlopen.c:87)
==5444== by 0x489E35E: rcutils_load_shared_library (in /opt/ros/foxy/lib/librcutils.so)
==5444==
==5444== 177 bytes in 3 blocks are still reachable in loss record 13 of 20
==5444== at 0x483B7F3: malloc (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==5444== by 0x401F5DE: strdup (strdup.c:42)
==5444== by 0x400A5A9: _dl_map_object (dl-load.c:2168)
==5444== by 0x4015D46: dl_open_worker (dl-open.c:513)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x4015609: _dl_open (dl-open.c:837)
==5444== by 0x4AB634B: dlopen_doit (dlopen.c:66)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x4C1B9F2: _dl_catch_error (dl-error-skeleton.c:227)
==5444== by 0x4AB6B58: _dlerror_run (dlerror.c:170)
==5444== by 0x4AB63D9: dlopen@@GLIBC_2.2.5 (dlopen.c:87)
==5444== by 0x489E35E: rcutils_load_shared_library (in /opt/ros/foxy/lib/librcutils.so)
==5444==
==5444== 177 bytes in 3 blocks are still reachable in loss record 14 of 20
==5444== at 0x483B7F3: malloc (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==5444== by 0x400D5B7: _dl_new_object (dl-object.c:196)
==5444== by 0x4006E96: _dl_map_object_from_fd (dl-load.c:997)
==5444== by 0x400A61A: _dl_map_object (dl-load.c:2236)
==5444== by 0x4015D46: dl_open_worker (dl-open.c:513)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x4015609: _dl_open (dl-open.c:837)
==5444== by 0x4AB634B: dlopen_doit (dlopen.c:66)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x4C1B9F2: _dl_catch_error (dl-error-skeleton.c:227)
==5444== by 0x4AB6B58: _dlerror_run (dlerror.c:170)
==5444== by 0x4AB63D9: dlopen@@GLIBC_2.2.5 (dlopen.c:87)
==5444==
==5444== 450 bytes in 9 blocks are still reachable in loss record 15 of 20
==5444== at 0x483B7F3: malloc (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==5444== by 0x4008C82: open_path (dl-load.c:1882)
==5444== by 0x400A7A2: _dl_map_object (dl-load.c:2067)
==5444== by 0x400F514: openaux (dl-deps.c:64)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x400F962: _dl_map_object_deps (dl-deps.c:248)
==5444== by 0x4015DAF: dl_open_worker (dl-open.c:571)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x4015609: _dl_open (dl-open.c:837)
==5444== by 0x4AB634B: dlopen_doit (dlopen.c:66)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x4C1B9F2: _dl_catch_error (dl-error-skeleton.c:227)
==5444==
==5444== 609 bytes in 13 blocks are still reachable in loss record 16 of 20
==5444== at 0x483B7F3: malloc (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==5444== by 0x400D5B7: _dl_new_object (dl-object.c:196)
==5444== by 0x4006E96: _dl_map_object_from_fd (dl-load.c:997)
==5444== by 0x400A61A: _dl_map_object (dl-load.c:2236)
==5444== by 0x400F514: openaux (dl-deps.c:64)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x400F962: _dl_map_object_deps (dl-deps.c:248)
==5444== by 0x4015DAF: dl_open_worker (dl-open.c:571)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x4015609: _dl_open (dl-open.c:837)
==5444== by 0x4AB634B: dlopen_doit (dlopen.c:66)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444==
==5444== 3,729 bytes in 3 blocks are still reachable in loss record 17 of 20
==5444== at 0x483DD99: calloc (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==5444== by 0x400D283: _dl_new_object (dl-object.c:89)
==5444== by 0x4006E96: _dl_map_object_from_fd (dl-load.c:997)
==5444== by 0x400A61A: _dl_map_object (dl-load.c:2236)
==5444== by 0x4015D46: dl_open_worker (dl-open.c:513)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x4015609: _dl_open (dl-open.c:837)
==5444== by 0x4AB634B: dlopen_doit (dlopen.c:66)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x4C1B9F2: _dl_catch_error (dl-error-skeleton.c:227)
==5444== by 0x4AB6B58: _dlerror_run (dlerror.c:170)
==5444== by 0x4AB63D9: dlopen@@GLIBC_2.2.5 (dlopen.c:87)
==5444==
==5444== 5,112 bytes in 15 blocks are still reachable in loss record 18 of 20
==5444== at 0x483DD99: calloc (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==5444== by 0x401331C: _dl_check_map_versions (dl-version.c:274)
==5444== by 0x40160FC: dl_open_worker (dl-open.c:577)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x4015609: _dl_open (dl-open.c:837)
==5444== by 0x4AB634B: dlopen_doit (dlopen.c:66)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x4C1B9F2: _dl_catch_error (dl-error-skeleton.c:227)
==5444== by 0x4AB6B58: _dlerror_run (dlerror.c:170)
==5444== by 0x4AB63D9: dlopen@@GLIBC_2.2.5 (dlopen.c:87)
==5444== by 0x489E35E: rcutils_load_shared_library (in /opt/ros/foxy/lib/librcutils.so)
==5444== by 0x4D24D34: rcpputils::SharedLibrary::SharedLibrary(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&) (in /opt/ros/foxy/lib/librcpputils.so)
==5444==
==5444== 15,739 bytes in 13 blocks are still reachable in loss record 19 of 20
==5444== at 0x483DD99: calloc (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==5444== by 0x400D283: _dl_new_object (dl-object.c:89)
==5444== by 0x4006E96: _dl_map_object_from_fd (dl-load.c:997)
==5444== by 0x400A61A: _dl_map_object (dl-load.c:2236)
==5444== by 0x400F514: openaux (dl-deps.c:64)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x400F962: _dl_map_object_deps (dl-deps.c:248)
==5444== by 0x4015DAF: dl_open_worker (dl-open.c:571)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x4015609: _dl_open (dl-open.c:837)
==5444== by 0x4AB634B: dlopen_doit (dlopen.c:66)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444==
==5444== 16,288 bytes in 1 blocks are still reachable in loss record 20 of 20
==5444== at 0x483DD99: calloc (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==5444== by 0x400BEA2: do_lookup_unique (dl-lookup.c:276)
==5444== by 0x400BEA2: do_lookup_x (dl-lookup.c:557)
==5444== by 0x400C1F0: _dl_lookup_symbol_x (dl-lookup.c:861)
==5444== by 0x400DF23: elf_machine_rela (dl-machine.h:308)
==5444== by 0x400DF23: elf_dynamic_do_Rela (do-rel.h:137)
==5444== by 0x400DF23: _dl_relocate_object (dl-reloc.c:255)
==5444== by 0x4015F6B: dl_open_worker (dl-open.c:688)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x4015609: _dl_open (dl-open.c:837)
==5444== by 0x4AB634B: dlopen_doit (dlopen.c:66)
==5444== by 0x4C1B927: _dl_catch_exception (dl-error-skeleton.c:208)
==5444== by 0x4C1B9F2: _dl_catch_error (dl-error-skeleton.c:227)
==5444== by 0x4AB6B58: _dlerror_run (dlerror.c:170)
==5444== by 0x4AB63D9: dlopen@@GLIBC_2.2.5 (dlopen.c:87)
==5444==
==5444== LEAK SUMMARY:
==5444== definitely lost: 128 bytes in 2 blocks
==5444== indirectly lost: 144 bytes in 2 blocks
==5444== possibly lost: 0 bytes in 0 blocks
==5444== still reachable: 43,104 bytes in 73 blocks
==5444== suppressed: 0 bytes in 0 blocks
==5444==
==5444== ERROR SUMMARY: 4 errors from 4 contexts (suppressed: 0 from 0)
==5444==
==5444== 1 errors in context 1 of 4:
==5444== Syscall param statx(buf) points to unaddressable byte(s)
==5444== at 0x4BC888E: statx (statx.c:29)
==5444== by 0x1F1EE1: statx (weak.rs:178)
==5444== by 0x1F1EE1: std::sys::unix::fs::try_statx (fs.rs:150)
==5444== by 0x1EE657: std::sys::unix::fs::stat (fs.rs:1255)
==5444== by 0x19AF07: metadata<&std::path::PathBuf> (fs.rs:1633)
==5444== by 0x19AF07: get_dbpath_for_term (searcher.rs:50)
==5444== by 0x19AF07: from_name (mod.rs:83)
==5444== by 0x19AF07: from_env (mod.rs:69)
==5444== by 0x19AF07: new<std::io::stdio::Stdout> (mod.rs:159)
==5444== by 0x19AF07: test::term::stdout (term.rs:33)
==5444== by 0x187C23: test::console::run_tests_console (console.rs:266)
==5444== by 0x19D226: test::test_main (lib.rs:115)
==5444== by 0x19E200: test::test_main_static (lib.rs:134)
==5444== by 0x166662: rclrs::main (lib.rs:1)
==5444== by 0x13C44A: core::ops::function::FnOnce::call_once (function.rs:227)
==5444== by 0x15A5AD: std::sys_common::backtrace::__rust_begin_short_backtrace (backtrace.rs:122)
==5444== by 0x157EE0: std::rt::lang_start::{{closure}} (rt.rs:145)
==5444== by 0x1E172D: call_once<(), (dyn core::ops::function::Fn<(), Output=i32> + core::marker::Sync + core::panic::unwind_safe::RefUnwindSafe)> (function.rs:259)
==5444== by 0x1E172D: do_call<&(dyn core::ops::function::Fn<(), Output=i32> + core::marker::Sync + core::panic::unwind_safe::RefUnwindSafe), i32> (panicking.rs:492)
==5444== by 0x1E172D: try<i32, &(dyn core::ops::function::Fn<(), Output=i32> + core::marker::Sync + core::panic::unwind_safe::RefUnwindSafe)> (panicking.rs:456)
==5444== by 0x1E172D: catch_unwind<&(dyn core::ops::function::Fn<(), Output=i32> + core::marker::Sync + core::panic::unwind_safe::RefUnwindSafe), i32> (panic.rs:137)
==5444== by 0x1E172D: {closure#2} (rt.rs:128)
==5444== by 0x1E172D: do_call<std::rt::lang_start_internal::{closure_env#2}, isize> (panicking.rs:492)
==5444== by 0x1E172D: try<isize, std::rt::lang_start_internal::{closure_env#2}> (panicking.rs:456)
==5444== by 0x1E172D: catch_unwind<std::rt::lang_start_internal::{closure_env#2}, isize> (panic.rs:137)
==5444== by 0x1E172D: std::rt::lang_start_internal (rt.rs:128)
==5444== Address 0x0 is not stack'd, malloc'd or (recently) free'd
==5444==
==5444==
==5444== 1 errors in context 2 of 4:
==5444== Syscall param statx(file_name) points to unaddressable byte(s)
==5444== at 0x4BC888E: statx (statx.c:29)
==5444== by 0x1F1EE1: statx (weak.rs:178)
==5444== by 0x1F1EE1: std::sys::unix::fs::try_statx (fs.rs:150)
==5444== by 0x1EE657: std::sys::unix::fs::stat (fs.rs:1255)
==5444== by 0x19AF07: metadata<&std::path::PathBuf> (fs.rs:1633)
==5444== by 0x19AF07: get_dbpath_for_term (searcher.rs:50)
==5444== by 0x19AF07: from_name (mod.rs:83)
==5444== by 0x19AF07: from_env (mod.rs:69)
==5444== by 0x19AF07: new<std::io::stdio::Stdout> (mod.rs:159)
==5444== by 0x19AF07: test::term::stdout (term.rs:33)
==5444== by 0x187C23: test::console::run_tests_console (console.rs:266)
==5444== by 0x19D226: test::test_main (lib.rs:115)
==5444== by 0x19E200: test::test_main_static (lib.rs:134)
==5444== by 0x166662: rclrs::main (lib.rs:1)
==5444== by 0x13C44A: core::ops::function::FnOnce::call_once (function.rs:227)
==5444== by 0x15A5AD: std::sys_common::backtrace::__rust_begin_short_backtrace (backtrace.rs:122)
==5444== by 0x157EE0: std::rt::lang_start::{{closure}} (rt.rs:145)
==5444== by 0x1E172D: call_once<(), (dyn core::ops::function::Fn<(), Output=i32> + core::marker::Sync + core::panic::unwind_safe::RefUnwindSafe)> (function.rs:259)
==5444== by 0x1E172D: do_call<&(dyn core::ops::function::Fn<(), Output=i32> + core::marker::Sync + core::panic::unwind_safe::RefUnwindSafe), i32> (panicking.rs:492)
==5444== by 0x1E172D: try<i32, &(dyn core::ops::function::Fn<(), Output=i32> + core::marker::Sync + core::panic::unwind_safe::RefUnwindSafe)> (panicking.rs:456)
==5444== by 0x1E172D: catch_unwind<&(dyn core::ops::function::Fn<(), Output=i32> + core::marker::Sync + core::panic::unwind_safe::RefUnwindSafe), i32> (panic.rs:137)
==5444== by 0x1E172D: {closure#2} (rt.rs:128)
==5444== by 0x1E172D: do_call<std::rt::lang_start_internal::{closure_env#2}, isize> (panicking.rs:492)
==5444== by 0x1E172D: try<isize, std::rt::lang_start_internal::{closure_env#2}> (panicking.rs:456)
==5444== by 0x1E172D: catch_unwind<std::rt::lang_start_internal::{closure_env#2}, isize> (panic.rs:137)
==5444== by 0x1E172D: std::rt::lang_start_internal (rt.rs:128)
==5444== Address 0x0 is not stack'd, malloc'd or (recently) free'd
==5444==
==5444== ERROR SUMMARY: 4 errors from 4 contexts (suppressed: 0 from 0)
Example places where leak occurs: context.rs, subscription.rs, node.rs.
Seems like deallocation is currently not utilized. For every rcl_init
call there should be corresponding deallocate
from rcl_allocator
.
FYI @ros2-rust/dev
Thanks for the report! ~I suspect most of these will be fixed by https://github.com/ros2-rust/ros2_rust/issues/188 – you probably terminated the application with Ctrl-C
, right? Would be interesting to do this for a program that terminates voluntarily.~
Nevermind, I should have read your description more closely.
We do have a corresponding fini()
call to each init()
call (usually in the Drop
impl). So I think the links you provided are not the true source of the leaks, and the Valgrind traces confirm this. Most of them are related to loading the typesupport library instead. I'm not sure what can be done about this.
Most of them are related to loading the typesupport library instead.
Does this mean that there's potentially a leak in ROS 2? Or am I misreading this?
I ran the C++ talker/listener demo from Rolling in Valgrind and saw no memory leaks. But I'm also not seeing any memory leaks when I run the rclrs
unit tests on the main
branch:
$ valgrind --tool=memcheck --leak-check=full -- target/debug/deps/rclrs-bf2ac4d893bc907f
==699039== Memcheck, a memory error detector
==699039== Copyright (C) 2002-2017, and GNU GPL'd, by Julian Seward et al.
==699039== Using Valgrind-3.18.1 and LibVEX; rerun with -h for copyright info
==699039== Command: target/debug/deps/rclrs-bf2ac4d893bc907f
==699039==
running 11 tests
test context::tests::test_create_context ... ok
test context::tests::test_context_ok ... ok
test parameter::value::tests::test_parameter_value ... ok
test parameter::override_map::tests::test_resolve_parameter_overrides ... ok
test node::subscription::tests::test_instantiate_subscriber ... ok
test node::publisher::tests::test_publish_message ... ok
test node::publisher::tests::test_new_publisher ... ok
test tests::test_spin_once ... ok
test node::tests::test_create_publisher ... ok
test node::tests::test_create_subscription ... ok
test node::tests::test_new ... ok
test result: ok. 11 passed; 0 failed; 0 ignored; 0 measured; 0 filtered out; finished in 15.30s
==699039==
==699039== HEAP SUMMARY:
==699039== in use at exit: 32,660 bytes in 86 blocks
==699039== total heap usage: 42,439 allocs, 42,353 frees, 16,481,316 bytes allocated
==699039==
==699039== LEAK SUMMARY:
==699039== definitely lost: 0 bytes in 0 blocks
==699039== indirectly lost: 0 bytes in 0 blocks
==699039== possibly lost: 0 bytes in 0 blocks
==699039== still reachable: 32,660 bytes in 86 blocks
==699039== suppressed: 0 bytes in 0 blocks
==699039== Reachable blocks (those to which a pointer was found) are not shown.
==699039== To see them, rerun with: --leak-check=full --show-leak-kinds=all
==699039==
==699039== For lists of detected and suppressed errors, rerun with: -s
==699039== ERROR SUMMARY: 0 errors from 0 contexts (suppressed: 0 from 0)
Which ROS distribution are you using, @Nizerlak?
I'm using Foxy.