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

Memory leak about not to call placement delete after calling placement new #219

Closed
iuhilnehc-ynos opened this issue Aug 13, 2020 · 15 comments
Labels
bug Something isn't working

Comments

@iuhilnehc-ynos
Copy link

iuhilnehc-ynos commented Aug 13, 2020

Bug report

Required Info:

  • Operating System:
    • Ubuntu 20.04
  • Installation type:
    • source
  • Version or commit hash:
  • DDS implementation:
    • rmw_cyclonedds_cpp
  • Client library (if applicable):
    • rcl

Steps to reproduce issue

$ colcon build --cmake-args -DCMAKE_BUILD_TYPE=Debug --packages-up-to rcl
$ . install/setup.bash
$ valgrind --leak-check=full ./build/rcl/test/test_node__rmw_cyclonedds_cpp --gtest_filter=*test_rcl_node_accessors*

Expected behavior

No memory leak about x = std::string(data + pos, sz - 1); in cycdeser::deserialize

Actual behavior

==668117== 29 bytes in 1 blocks are definitely lost in loss record 2 of 25
==668117==    at 0x483DE63: operator new(unsigned long) (in /usr/lib/x86_64-linux-gnu/valgrind/vgpreload_memcheck-amd64-linux.so)
==668117==    by 0x255608: void std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >::_M_construct<char const*>(char const*, char const*, std::forward_iterator_tag) (basic_string.tcc:219)
==668117==    by 0x5176382: cycdeser::deserialize(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >&) (serdes.hpp:165)
==668117==    by 0x5175CC4: cycdeser::operator>>(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >&) (serdes.hpp:113)
==668117==    by 0x517724A: void rmw_cyclonedds_cpp::deserialize_field<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > >(rosidl_typesupport_introspection_cpp::MessageMember const*, void*, cycdeser&, bool) (TypeSupport_impl.hpp:281)
==668117==    by 0x518220C: rmw_cyclonedds_cpp::TypeSupport<rosidl_typesupport_introspection_cpp::MessageMembers>::deserializeROSmessage(cycdeser&, rosidl_typesupport_introspection_cpp::MessageMembers const*, void*, bool) (TypeSupport_impl.hpp:514)
==668117==    by 0x5182350: rmw_cyclonedds_cpp::TypeSupport<rosidl_typesupport_introspection_cpp::MessageMembers>::deserializeROSmessage(cycdeser&, rosidl_typesupport_introspection_cpp::MessageMembers const*, void*, bool) (TypeSupport_impl.hpp:542)
==668117==    by 0x517BB3E: rmw_cyclonedds_cpp::TypeSupport<rosidl_typesupport_introspection_cpp::MessageMembers>::deserializeROSmessage(cycdeser&, void*, std::function<void (cycdeser&)>) (TypeSupport_impl.hpp:669)
==668117==    by 0x51D10CF: serdata_rmw_to_sample(ddsi_serdata const*, void*, void**, void*) (serdata.cpp:288)
==668117==    by 0x57EDAD8: ddsi_serdata_to_sample (ddsi_serdata.h:230)
==668117==    by 0x586E9EC: read_take_to_sample (dds_rhc_default.c:1956)
==668117==    by 0x586F15B: take_w_qminv_inst (dds_rhc_default.c:2091)

... <and another type of memory leak about `create_message_type_support` that not destroyed which I've already known how to fix it.>

Additional information

  • backtrace of main steps:

    new(field) std::string()

    (gdb) bt
    #0  rmw_cyclonedds_cpp::deserialize_field<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > > (
        member=0x7ffff754a5c0 <rmw_dds_common::msg::rosidl_typesupport_introspection_cpp::NodeEntitiesInfo_message_member_array>, field=0x7fffdc0018d0, deser=..., call_new=true)
        at /home/ros2_ws/src/ros2/rmw_cyclonedds/rmw_cyclonedds_cpp/include/rmw_cyclonedds_cpp/TypeSupport_impl.hpp:279
    #1  0x00007ffff76a420d in rmw_cyclonedds_cpp::TypeSupport<rosidl_typesupport_introspection_cpp::MessageMembers>::deserializeROSmessage (this=0x55555570d800, deser=..., 
        members=0x7ffff7549d40 <rmw_dds_common::msg::rosidl_typesupport_introspection_cpp::NodeEntitiesInfo_message_members>, ros_message=0x7fffdc0018d0, call_new=true)
        at /home/ros2_ws/src/ros2/rmw_cyclonedds/rmw_cyclonedds_cpp/include/rmw_cyclonedds_cpp/TypeSupport_impl.hpp:514
    #2  0x00007ffff76a4351 in rmw_cyclonedds_cpp::TypeSupport<rosidl_typesupport_introspection_cpp::MessageMembers>::deserializeROSmessage (this=0x55555570d800, deser=..., 
        members=0x7ffff7549d80 <rmw_dds_common::msg::rosidl_typesupport_introspection_cpp::ParticipantEntitiesInfo_message_members>, ros_message=0x7ffff1bb5ad0, call_new=false)
        at /home/ros2_ws/src/ros2/rmw_cyclonedds/rmw_cyclonedds_cpp/include/rmw_cyclonedds_cpp/TypeSupport_impl.hpp:542
    #3  0x00007ffff769db3f in rmw_cyclonedds_cpp::TypeSupport<rosidl_typesupport_introspection_cpp::MessageMembers>::deserializeROSmessage(cycdeser&, void*, std::function<void (cycdeser&)>) (this=0x55555570d800, deser=..., ros_message=0x7ffff1bb5ad0, prefix=...)
        at /home/ros2_ws/src/ros2/rmw_cyclonedds/rmw_cyclonedds_cpp/include/rmw_cyclonedds_cpp/TypeSupport_impl.hpp:669
    #4  0x00007ffff76f30d0 in serdata_rmw_to_sample (dcmn=0x555555721210, sample=0x7ffff1bb5ad0, bufptr=0x0, buflim=0x0)
        at /home/ros2_ws/src/ros2/rmw_cyclonedds/rmw_cyclonedds_cpp/src/serdata.cpp:288
    #5  0x00007ffff6f71ad9 in ddsi_serdata_to_sample (d=0x555555721210, sample=0x7ffff1bb5ad0, bufptr=0x0, buflim=0x0)
        at /home/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/security/api/../../core/ddsi/include/dds/ddsi/ddsi_serdata.h:230
    #6  0x00007ffff6ff29ed in read_take_to_sample (d=0x555555721210, sample=0x7ffff1bb5a00, bufptr=0x0, buflim=0x0)
        at /home/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsc/src/dds_rhc_default.c:1956
    #7  0x00007ffff6ff315c in take_w_qminv_inst (rhc=0x555555712ea0, instptr=0x7ffff1bb56e0, values=0x7ffff1bb5a00, info_seq=0x7ffff1bb5a20, max_samples=1, qminv=0, qcmask=0, 
        ntriggers=0x7ffff1bb56d8, to_sample=0x7ffff6ff29b6 <read_take_to_sample>, to_invsample=0x7ffff6ff29ef <read_take_to_invsample>)
        at /home/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsc/src/dds_rhc_default.c:2091
    #8  0x00007ffff6ff3cae in take_w_qminv (rhc=0x555555712ea0, lock=true, values=0x7ffff1bb5a00, info_seq=0x7ffff1bb5a20, max_samples=1, qminv=0, handle=0, cond=0x0, 
        to_sample=0x7ffff6ff29b6 <read_take_to_sample>, to_invsample=0x7ffff6ff29ef <read_take_to_invsample>)
        at /home/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsc/src/dds_rhc_default.c:2227
    #9  0x00007ffff6ff3ec3 in dds_rhc_take_w_qminv (rhc=0x555555712ea0, lock=true, values=0x7ffff1bb5a00, info_seq=0x7ffff1bb5a20, max_samples=1, qminv=0, handle=0, cond=0x0)
        at /home/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsc/src/dds_rhc_default.c:2251
    #10 0x00007ffff6ff5a5c in dds_rhc_default_take (rhc_common=0x555555712ea0, lock=true, values=0x7ffff1bb5a00, info_seq=0x7ffff1bb5a20, max_samples=1, mask=128, handle=0, cond=0x0)
        at /home/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsc/src/dds_rhc_default.c:2663
    #11 0x00007ffff6fedc71 in dds_rhc_take (rhc=0x555555712ea0, lock=true, values=0x7ffff1bb5a00, info_seq=0x7ffff1bb5a20, max_samples=1, mask=128, handle=0, cond=0x0)
        at /home/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsc/include/dds/ddsc/dds_rhc.h:83
    #12 0x00007ffff7002767 in dds_read_impl (take=true, reader_or_condition=153907983, buf=0x7ffff1bb5a00, bufsz=1, maxs=1, si=0x7ffff1bb5a20, mask=128, hand=0, lock=true, 
        only_reader=false) at /home/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsc/src/dds_read.c:111
    #13 0x00007ffff7002fc4 in dds_take (rd_or_cnd=153907983, buf=0x7ffff1bb5a00, si=0x7ffff1bb5a20, bufsz=1, maxs=1)
        at /home/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsc/src/dds_read.c:332
    #14 0x00007ffff768c45c in rmw_take_int (subscription=0x555555713730, ros_message=0x7ffff1bb5ad0, taken=0x7ffff1bb5ac7, message_info=0x0)
        at /home/ros2_ws/src/ros2/rmw_cyclonedds/rmw_cyclonedds_cpp/src/rmw_node.cpp:2487
    #15 0x00007ffff768ce44 in rmw_take (subscription=0x555555713730, ros_message=0x7ffff1bb5ad0, taken=0x7ffff1bb5ac7, allocation=0x0)
        at /home/ros2_ws/src/ros2/rmw_cyclonedds/rmw_cyclonedds_cpp/src/rmw_node.cpp:2643
    #16 0x00007ffff7682202 in handle_ParticipantEntitiesInfo (reader=153907983, arg=0x5555556f16a0)
        at /home/ros2_ws/src/ros2/rmw_cyclonedds/rmw_cyclonedds_cpp/src/rmw_node.cpp:556
    #17 0x00007ffff76a27ba in std::_Function_handler<void (int, rmw_context_impl_t*), void (*)(int, void*)>::_M_invoke(std::_Any_data const&, int&&, rmw_context_impl_t*&&) (
    --Type <RET> for more, q to quit, c to continue without paging--
        __functor=..., __args#0=@0x7ffff1bb5b84: 153907983, __args#1=@0x7ffff1bb5b78: 0x5555556f16a0) at /usr/include/c++/9/bits/std_function.h:300
    #18 0x00007ffff769caec in std::function<void (int, rmw_context_impl_t*)>::operator()(int, rmw_context_impl_t*) const (this=0x7fffdc000e70, __args#0=153907983, 
        __args#1=0x5555556f16a0) at /usr/include/c++/9/bits/std_function.h:688
    #19 0x00007ffff7682d23 in discovery_thread (impl=0x5555556f16a0) at /home/ros2_ws/src/ros2/rmw_cyclonedds/rmw_cyclonedds_cpp/src/rmw_node.cpp:677
    #20 0x00007ffff76f2293 in std::__invoke_impl<void, void (*)(rmw_context_impl_t*), rmw_context_impl_t*> (__f=@0x555555713360: 0x7ffff7682839 <discovery_thread(rmw_context_impl_t*)>)
        at /usr/include/c++/9/bits/invoke.h:60
    #21 0x00007ffff76f21df in std::__invoke<void (*)(rmw_context_impl_t*), rmw_context_impl_t*> (__fn=@0x555555713360: 0x7ffff7682839 <discovery_thread(rmw_context_impl_t*)>)
        at /usr/include/c++/9/bits/invoke.h:95
    #22 0x00007ffff76f212f in std::thread::_Invoker<std::tuple<void (*)(rmw_context_impl_t*), rmw_context_impl_t*> >::_M_invoke<0ul, 1ul> (this=0x555555713358)
        at /usr/include/c++/9/thread:244
    #23 0x00007ffff76f205b in std::thread::_Invoker<std::tuple<void (*)(rmw_context_impl_t*), rmw_context_impl_t*> >::operator() (this=0x555555713358) at /usr/include/c++/9/thread:251
    #24 0x00007ffff76f1fe4 in std::thread::_State_impl<std::thread::_Invoker<std::tuple<void (*)(rmw_context_impl_t*), rmw_context_impl_t*> > >::_M_run (this=0x555555713350)
        at /usr/include/c++/9/thread:195
    #25 0x00007ffff7402cb4 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
    #26 0x00007ffff72f7609 in start_thread (arg=<optimized out>) at pthread_create.c:477
    #27 0x00007ffff721e103 in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95

    assign string (a bit length) into buffer which will cause string::data() be reconstructed.

    #0  cycdeser::deserialize (this=0x7ffff1bb54c0, x="")
        at /home/ros2_ws/src/ros2/rmw_cyclonedds/rmw_cyclonedds_cpp/include/rmw_cyclonedds_cpp/serdes.hpp:165
    #1  0x00007ffff7697cc5 in cycdeser::operator>> (this=0x7ffff1bb54c0, x="")
        at /home/ros2_ws/src/ros2/rmw_cyclonedds/rmw_cyclonedds_cpp/include/rmw_cyclonedds_cpp/serdes.hpp:113
    #2  0x00007ffff769924b in rmw_cyclonedds_cpp::deserialize_field<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > > (
        member=0x7ffff754a620 <rmw_dds_common::msg::rosidl_typesupport_introspection_cpp::NodeEntitiesInfo_message_member_array+96>, field=0x7fffdc0018f0, deser=..., call_new=true)
        at /home/ros2_ws/src/ros2/rmw_cyclonedds/rmw_cyclonedds_cpp/include/rmw_cyclonedds_cpp/TypeSupport_impl.hpp:281
    #3  0x00007ffff76a420d in rmw_cyclonedds_cpp::TypeSupport<rosidl_typesupport_introspection_cpp::MessageMembers>::deserializeROSmessage (this=0x55555570d800, deser=..., 
        members=0x7ffff7549d40 <rmw_dds_common::msg::rosidl_typesupport_introspection_cpp::NodeEntitiesInfo_message_members>, ros_message=0x7fffdc0018d0, call_new=true)
        at /home/ros2_ws/src/ros2/rmw_cyclonedds/rmw_cyclonedds_cpp/include/rmw_cyclonedds_cpp/TypeSupport_impl.hpp:514
    #4  0x00007ffff76a4351 in rmw_cyclonedds_cpp::TypeSupport<rosidl_typesupport_introspection_cpp::MessageMembers>::deserializeROSmessage (this=0x55555570d800, deser=..., 
        members=0x7ffff7549d80 <rmw_dds_common::msg::rosidl_typesupport_introspection_cpp::ParticipantEntitiesInfo_message_members>, ros_message=0x7ffff1bb5ad0, call_new=false)
        at /home/ros2_ws/src/ros2/rmw_cyclonedds/rmw_cyclonedds_cpp/include/rmw_cyclonedds_cpp/TypeSupport_impl.hpp:542
    #5  0x00007ffff769db3f in rmw_cyclonedds_cpp::TypeSupport<rosidl_typesupport_introspection_cpp::MessageMembers>::deserializeROSmessage(cycdeser&, void*, std::function<void (cycdeser&)>) (this=0x55555570d800, deser=..., ros_message=0x7ffff1bb5ad0, prefix=...)
        at /home/ros2_ws/src/ros2/rmw_cyclonedds/rmw_cyclonedds_cpp/include/rmw_cyclonedds_cpp/TypeSupport_impl.hpp:669
    #6  0x00007ffff76f30d0 in serdata_rmw_to_sample (dcmn=0x555555721210, sample=0x7ffff1bb5ad0, bufptr=0x0, buflim=0x0)
        at /home/ros2_ws/src/ros2/rmw_cyclonedds/rmw_cyclonedds_cpp/src/serdata.cpp:288
    #7  0x00007ffff6f71ad9 in ddsi_serdata_to_sample (d=0x555555721210, sample=0x7ffff1bb5ad0, bufptr=0x0, buflim=0x0)
        at /home/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/security/api/../../core/ddsi/include/dds/ddsi/ddsi_serdata.h:230
    #8  0x00007ffff6ff29ed in read_take_to_sample (d=0x555555721210, sample=0x7ffff1bb5a00, bufptr=0x0, buflim=0x0)
        at /home/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsc/src/dds_rhc_default.c:1956
    #9  0x00007ffff6ff315c in take_w_qminv_inst (rhc=0x555555712ea0, instptr=0x7ffff1bb56e0, values=0x7ffff1bb5a00, info_seq=0x7ffff1bb5a20, max_samples=1, qminv=0, qcmask=0, 
        ntriggers=0x7ffff1bb56d8, to_sample=0x7ffff6ff29b6 <read_take_to_sample>, to_invsample=0x7ffff6ff29ef <read_take_to_invsample>)
        at /home/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsc/src/dds_rhc_default.c:2091
    #10 0x00007ffff6ff3cae in take_w_qminv (rhc=0x555555712ea0, lock=true, values=0x7ffff1bb5a00, info_seq=0x7ffff1bb5a20, max_samples=1, qminv=0, handle=0, cond=0x0, 
        to_sample=0x7ffff6ff29b6 <read_take_to_sample>, to_invsample=0x7ffff6ff29ef <read_take_to_invsample>)
        at /home/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsc/src/dds_rhc_default.c:2227
    #11 0x00007ffff6ff3ec3 in dds_rhc_take_w_qminv (rhc=0x555555712ea0, lock=true, values=0x7ffff1bb5a00, info_seq=0x7ffff1bb5a20, max_samples=1, qminv=0, handle=0, cond=0x0)
        at /home/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsc/src/dds_rhc_default.c:2251
    #12 0x00007ffff6ff5a5c in dds_rhc_default_take (rhc_common=0x555555712ea0, lock=true, values=0x7ffff1bb5a00, info_seq=0x7ffff1bb5a20, max_samples=1, mask=128, handle=0, cond=0x0)
        at /home/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsc/src/dds_rhc_default.c:2663
    #13 0x00007ffff6fedc71 in dds_rhc_take (rhc=0x555555712ea0, lock=true, values=0x7ffff1bb5a00, info_seq=0x7ffff1bb5a20, max_samples=1, mask=128, handle=0, cond=0x0)
        at /home/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsc/include/dds/ddsc/dds_rhc.h:83
    #14 0x00007ffff7002767 in dds_read_impl (take=true, reader_or_condition=153907983, buf=0x7ffff1bb5a00, bufsz=1, maxs=1, si=0x7ffff1bb5a20, mask=128, hand=0, lock=true, 
        only_reader=false) at /home/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsc/src/dds_read.c:111
    #15 0x00007ffff7002fc4 in dds_take (rd_or_cnd=153907983, buf=0x7ffff1bb5a00, si=0x7ffff1bb5a20, bufsz=1, maxs=1)
        at /home/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsc/src/dds_read.c:332
    #16 0x00007ffff768c45c in rmw_take_int (subscription=0x555555713730, ros_message=0x7ffff1bb5ad0, taken=0x7ffff1bb5ac7, message_info=0x0)
        at /home/ros2_ws/src/ros2/rmw_cyclonedds/rmw_cyclonedds_cpp/src/rmw_node.cpp:2487
    #17 0x00007ffff768ce44 in rmw_take (subscription=0x555555713730, ros_message=0x7ffff1bb5ad0, taken=0x7ffff1bb5ac7, allocation=0x0)
    --Type <RET> for more, q to quit, c to continue without paging--
        at /home/ros2_ws/src/ros2/rmw_cyclonedds/rmw_cyclonedds_cpp/src/rmw_node.cpp:2643
    #18 0x00007ffff7682202 in handle_ParticipantEntitiesInfo (reader=153907983, arg=0x5555556f16a0)
        at /home/ros2_ws/src/ros2/rmw_cyclonedds/rmw_cyclonedds_cpp/src/rmw_node.cpp:556
    #19 0x00007ffff76a27ba in std::_Function_handler<void (int, rmw_context_impl_t*), void (*)(int, void*)>::_M_invoke(std::_Any_data const&, int&&, rmw_context_impl_t*&&) (
        __functor=..., __args#0=@0x7ffff1bb5b84: 153907983, __args#1=@0x7ffff1bb5b78: 0x5555556f16a0) at /usr/include/c++/9/bits/std_function.h:300
    #20 0x00007ffff769caec in std::function<void (int, rmw_context_impl_t*)>::operator()(int, rmw_context_impl_t*) const (this=0x7fffdc000e70, __args#0=153907983, 
        __args#1=0x5555556f16a0) at /usr/include/c++/9/bits/std_function.h:688
    #21 0x00007ffff7682d23 in discovery_thread (impl=0x5555556f16a0) at /home/ros2_ws/src/ros2/rmw_cyclonedds/rmw_cyclonedds_cpp/src/rmw_node.cpp:677
    #22 0x00007ffff76f2293 in std::__invoke_impl<void, void (*)(rmw_context_impl_t*), rmw_context_impl_t*> (__f=@0x555555713360: 0x7ffff7682839 <discovery_thread(rmw_context_impl_t*)>)
        at /usr/include/c++/9/bits/invoke.h:60
    #23 0x00007ffff76f21df in std::__invoke<void (*)(rmw_context_impl_t*), rmw_context_impl_t*> (__fn=@0x555555713360: 0x7ffff7682839 <discovery_thread(rmw_context_impl_t*)>)
        at /usr/include/c++/9/bits/invoke.h:95
    #24 0x00007ffff76f212f in std::thread::_Invoker<std::tuple<void (*)(rmw_context_impl_t*), rmw_context_impl_t*> >::_M_invoke<0ul, 1ul> (this=0x555555713358)
        at /usr/include/c++/9/thread:244
    #25 0x00007ffff76f205b in std::thread::_Invoker<std::tuple<void (*)(rmw_context_impl_t*), rmw_context_impl_t*> >::operator() (this=0x555555713358) at /usr/include/c++/9/thread:251
    #26 0x00007ffff76f1fe4 in std::thread::_State_impl<std::thread::_Invoker<std::tuple<void (*)(rmw_context_impl_t*), rmw_context_impl_t*> > >::_M_run (this=0x555555713350)
        at /usr/include/c++/9/thread:195
    #27 0x00007ffff7402cb4 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
    #28 0x00007ffff72f7609 in start_thread (arg=<optimized out>) at pthread_create.c:477
    #29 0x00007ffff721e103 in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95

  • main sequence

        handle_ParticipantEntitiesInfo
            ParticipantEntitiesInfo msg;
            rmw_take->...->take_w_qminv_inst->
                to_sample
                  serdata_rmw_to_sample   // call `new(field) std::string()` inside
                free_sample
                  serdata_rmw_free        // It seems it's the best place to call `operator delete` here, but `msg` will be used after it.
                                          // NOTE: I had tried to save the `field` pointer into a list, and `operator delete` it. 
            impl->common.graph_cache.update_participant_entities(msg);
    

Could somebody give me a suggestion?

This issue is related to ros2/rcl#721, but I think it belongs to rmw_cyclonedds.

@eboasson
Copy link
Collaborator

@iuhilnehc-ynos thank you for looking into this!

I guess I had assumed that:

  1. Leaving the scope containing msg would run a destructor that frees the memory;
  2. If two (or more) messages get processed in the loop the deserializer would reuse the memory allocated for the preceding message.

I may have been thinking of how Cyclone DDS's native code for copying samples out to C applications handles things in making the second assumption. For some background: I borrowed the deserializer code from the dynamic Fast-RTPS RMW implementation some two years ago, hacking it to fit my needs and without ever really diving into the details, and especially without understanding what/when call_new is needed. It is definitely possible that I either screwed up in that process or that I copied a bug that's been fixed a long time ago.

If the destructor does free the memory, the easy solution would be to change the scope of msg so it gets destructed after each successful call to take. It could even be that that's the intent behind the RMW interface without my realizing it.

The calls to serdata_rmw_free release the internal message representation in Cyclone DDS after the message has been deserialized in the ROS message, so that's not the place to free this memory.

@iuhilnehc-ynos
Copy link
Author

@eboasson
thanks for your quick reply.

deserializer code from the dynamic Fast-RTPS RMW implementation

I quickly checked the rmw_fastrtps, and found it still uses new(field) std::string(). The next thing I need to do is check how/where dynamic Fast-RTPS RMW implementation to free it.

The calls to serdata_rmw_free release the internal message representation in Cyclone DDS after the message has been deserialized in the ROS message, so that's not the place to free this memory.

I agree with this.

@iuhilnehc-ynos
Copy link
Author

@eboasson

If the destructor does free the memory, the easy solution would be to change the scope of msg so it gets destructed after each successful call to take

Sorry, I lost this important information. And after checking, I think it's the reason why string not deleted.
I have made a PR, could you help me review it, please?

@ivanpauno
Copy link
Member

ivanpauno commented Aug 26, 2020

Summary of discussion in #224, which works around the issue but doesn't fix the problem.
The problem is in the typesupport implementation:

  • Doing a reinterpret_cast of a std::vector<MessageT> to a std::vector<unsigned char> * is extremely unsafe (here) and may not work in many stl implementations (I'm even surprised this is working at all, isn't size/capacity corrupted when resizing?).
  • Placement new should never be called on a passed message (used after resizing a vector because of the unsafe reinterpret_cast above, see here), that corrupts the memory of previously allocated objects and causes leaks.

@iuhilnehc-ynos
Copy link
Author

@ivanpauno

Thanks for your explanation.
I believe you're right. At

inline size_t get_submessage_array_deserialize(
, it should call resize_function and get_function of MessageMember if these functions exist.

I checked the participant_entities_info__type_support.cpp

static const ::rosidl_typesupport_introspection_cpp::MessageMember ParticipantEntitiesInfo_message_member_array[2] = {
  ...
  {
    "node_entities_info_seq",  // name
    ::rosidl_typesupport_introspection_cpp::ROS_TYPE_MESSAGE,  // type
    0,  // upper bound of string
    ::rosidl_typesupport_introspection_cpp::get_message_type_support_handle<rmw_dds_common::msg::NodeEntitiesInfo>(),  // members of sub message
    true,  // is array
    0,  // array size
    false,  // is upper bound
    offsetof(rmw_dds_common::msg::ParticipantEntitiesInfo, node_entities_info_seq),  // bytes offset in struct
    nullptr,  // default value
    size_function__ParticipantEntitiesInfo__node_entities_info_seq,  // size() function pointer
    get_const_function__ParticipantEntitiesInfo__node_entities_info_seq,  // get_const(index) function pointer
    get_function__ParticipantEntitiesInfo__node_entities_info_seq,  // get(index) function pointer
    resize_function__ParticipantEntitiesInfo__node_entities_info_seq  // resize(index) function pointer
  }

Currently, these functions(such as, get_function__ParticipantEntitiesInfo__node_entities_info_seq and resize_function__ParticipantEntitiesInfo__node_entities_info_seq) are just defined. There is no function to call them.
I'll try this way.

@iuhilnehc-ynos
Copy link
Author

iuhilnehc-ynos commented Aug 27, 2020

@ivanpauno

I have checked it. It's working(not to test more, maybe it's not the final patch.). (reverted my previous commit and just use the following patch)

diff --git a/rmw_cyclonedds_cpp/include/rmw_cyclonedds_cpp/TypeSupport_impl.hpp b/rmw_cyclonedds_cpp/include/rmw_cyclonedds_cpp/TypeSupport_impl.hpp
index bf2d229..d4e8782 100644
--- a/rmw_cyclonedds_cpp/include/rmw_cyclonedds_cpp/TypeSupport_impl.hpp
+++ b/rmw_cyclonedds_cpp/include/rmw_cyclonedds_cpp/TypeSupport_impl.hpp
@@ -436,14 +436,19 @@ inline size_t get_submessage_array_deserialize(
   size_t sub_members_size,
   size_t max_align)
 {
-  (void)member;
+//  (void)member;
   uint32_t vsize = deser.deserialize_len(1);
-  auto vector = reinterpret_cast<std::vector<unsigned char> *>(field);
-  if (call_new) {
-    new(vector) std::vector<unsigned char>;
+  if (member->resize_function && member->get_function) {
+    member->resize_function(field, vsize);
+    subros_message = member->get_function(field, 0);
+  } else {
+    auto vector = reinterpret_cast<std::vector<unsigned char> *>(field);
+    if (call_new) {
+      new(vector) std::vector<unsigned char>;
+    }
+    vector->resize(vsize * align_int_(max_align, sub_members_size));
+    subros_message = reinterpret_cast<void *>(vector->data());
   }
-  vector->resize(vsize * align_int_(max_align, sub_members_size));
-  subros_message = reinterpret_cast<void *>(vector->data());
   return vsize;
 }

I think this fix belongs to you.

@fujitatomoya
Copy link
Contributor

@iuhilnehc-ynos
CC: @ivanpauno

Do we actually need if (member->resize_function && member->get_function) ? these will be defined as followings. (just curious)

void * get_function__ParticipantEntitiesInfo__node_entities_info_seq(void * untyped_member, size_t index)
{
  auto & member =
    *reinterpret_cast<std::vector<rmw_dds_common::msg::NodeEntitiesInfo> *>(untyped_member);
  return &member[index];
}

void resize_function__ParticipantEntitiesInfo__node_entities_info_seq(void * untyped_member, size_t size)
{
  auto * member =
    reinterpret_cast<std::vector<rmw_dds_common::msg::NodeEntitiesInfo> *>(untyped_member);
  member->resize(size);
}

@iuhilnehc-ynos
Copy link
Author

iuhilnehc-ynos commented Aug 27, 2020

@fujitatomoya

Do we actually need if (member->resize_function && member->get_function) ?

Me too. I think I need to check the template if all members will define these functions when member matches the condition.(type_id_=ROS_TYPE_MESSAGE, is_array_=true, array_size_=0 or is_upper_bound_=true).

@iuhilnehc-ynos
Copy link
Author

if there is a vector, these functions will be nullptr.

My mistake. bool is ROS_TYPE_BOOLEAN, not a ROS_TYPE_MESSAGE.

@ivanpauno
Copy link
Member

ivanpauno commented Aug 27, 2020

I have checked it. It's working(not to test more, maybe it's not the final patch.). (reverted my previous commit and just use the following patch)

That patch is a good start but:

  • The else part shouldn't reinterpret the vector as std::vector<unsigned char>, instead it should fail (all ROS_TYPE_MESSAGE members must provide it).
    Reinterpreting a std::vector<X> as std::vector<unsigned char> is not allowed, and I'm amazed it was working in four different platforms 🤯 🤯 🤯. I even started reading libstdc++ implementation to understand why it was working, they store only pointers and not the size, so the reinterpret_cast works. Of course that's not guaranteed by the standard and shouldn't be done.
  • The resize function provided by the introspection typesupport calls the correct vector resize method, and thus all the placement news are unneeded. It would be great if we could get rid of all the call_new arguments and the placement news (that will fix the leaks and Fix memory leak that string not deleted. #224 can be reverted after that).

I probably won't have time to work on a fix til next week, so if somebody else wants to open a PR that would be great.

@ivanpauno
Copy link
Member

Do we actually need if (member->resize_function && member->get_function) ? these will be defined as followings. (just curious)

A sanity check isn't bad, but in that case the code should fail, as the function pointer being NULL would be unexepected.

@ivanpauno ivanpauno added the bug Something isn't working label Aug 27, 2020
@iuhilnehc-ynos
Copy link
Author

iuhilnehc-ynos commented Aug 28, 2020

I probably won't have time to work on a fix til next week, so if somebody else wants to open a PR that would be great.

I'd like to make a PR for it.

  • remove unnecessary source code
    • delete get_submessage_array_deserialize that we don't use them (including the c API for member)
  • use resize_function and get_function instead of get_submessage_array_deserialize
  • remove all call_new (including the argument of interfaces)
  • revert Fix memory leak that string not deleted. #224 commit

@ivanpauno
Copy link
Member

I thinks this was fixed by #228, thanks @iuhilnehc-ynos !!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working
Projects
None yet
Development

No branches or pull requests

4 participants