ros2 / rmw_cyclonedds

ROS 2 RMW layer for Eclipse Cyclone DDS
Apache License 2.0
108 stars 89 forks source link

Memory leak when using multi threaded application #502

Open stevedanomodolor opened 1 week ago

stevedanomodolor commented 1 week ago

Bug report

Required Info:

Steps to reproduce issue

I cant share the code because it is from a private database but it happens when I have a node which i run in thread A and has get functions that call service clients. Thread B is not a ros node, but another application running and this application calls the get functions. When the get functions are called, its calls service clients node this is where the problems begin. When this happens I get the following from thread analizer

[web_bridge-1] ==================
[web_bridge-1] WARNING: ThreadSanitizer: data race (pid=10878)
[web_bridge-1]   Write of size 1 at 0x7b14000629d0 by thread T2 (mutexes: write M1704):
[web_bridge-1]     #0 pthread_mutex_destroy ../../../../src/libsanitizer/tsan/tsan_interceptors_posix.cpp:1244 (libtsan.so.0+0x39398)
[web_bridge-1]     #1 ddsrt_mutex_destroy <null> (libddsc.so.0+0xe743c)
[web_bridge-1] 
[web_bridge-1]   Previous atomic read of size 1 at 0x7b14000629d0 by thread T10 (mutexes: write M1701, write M217434007850592720):
[web_bridge-1]     #0 pthread_mutex_unlock ../../../../src/libsanitizer/sanitizer_common/sanitizer_common_interceptors.inc:4254 (libtsan.so.0+0x3bff8)
[web_bridge-1]     #1 ddsrt_mutex_unlock <null> (libddsc.so.0+0xe74ec)
[web_bridge-1]     #2 rclcpp::Service<umd_robot_interfaces::srv::HasRobotDockingStation>::handle_request(std::shared_ptr<rmw_request_id_s>, std::shared_ptr<void>) /opt/ros/humble/include/rclcpp/rclcpp/service.hpp:475 (libweb_bridge_core.so+0x7778a6)
[web_bridge-1]     #3 <null> <null> (librclcpp.so+0xe9375)
[web_bridge-1]     #4 __invoke_impl<void, main(int, char**)::<lambda()> > /usr/include/c++/11/bits/invoke.h:61 (web_bridge+0xcc3d6)
[web_bridge-1]     #5 __invoke<main(int, char**)::<lambda()> > /usr/include/c++/11/bits/invoke.h:96 (web_bridge+0xcc2c4)
[web_bridge-1]     #6 _M_invoke<0> /usr/include/c++/11/bits/std_thread.h:259 (web_bridge+0xcc186)
[web_bridge-1]     #7 operator() /usr/include/c++/11/bits/std_thread.h:266 (web_bridge+0xcc0d2)
[web_bridge-1]     #8 _M_run /usr/include/c++/11/bits/std_thread.h:211 (web_bridge+0xcc03e)
[web_bridge-1]     #9 <null> <null> (libstdc++.so.6+0xdc252)
[web_bridge-1] 
[web_bridge-1]   Location is heap block of size 80 at 0x7b14000629d0 allocated by thread T3:
[web_bridge-1]     #0 malloc ../../../../src/libsanitizer/tsan/tsan_interceptors_posix.cpp:655 (libtsan.so.0+0x31c57)
[web_bridge-1]     #1 ddsrt_malloc <null> (libddsc.so.0+0xe434c)

Expected behavior

Stack trace (most recent call last) in thread 67:
#15   Object "", at 0xffffffffffffffff, in
#14   Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x7b030861aa03, in __clone
#13   Object "/usr/lib/x86_64-linux-gnu/libc.so.6", at 0x7b0308589ac2, in
#12   Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x7b030881c252, in
#11   Object "/umd2_ws/install/umd_utils/lib/libumd_utils.so", at 0x7b03089794b5, in std::thread::_State_impl<std::thread::_Invoker<std::tuple<umd_utils::NodeThread::NodeThread(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>)::{lambda()#1}> > >::_M_run()
#10   Object "/umd2_ws/install/umd_utils/lib/libumd_utils.so", at 0x7b03089794ed, in std::thread::_Invoker<std::tuple<umd_utils::NodeThread::NodeThread(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>)::{lambda()#1}> >::operator()()
#9    Object "/umd2_ws/install/umd_utils/lib/libumd_utils.so", at 0x7b0308979545, in void std::thread::_Invoker<std::tuple<umd_utils::NodeThread::NodeThread(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>)::{lambda()#1}> >::_M_invoke<0ul>(std::_Index_tuple<0ul>)
#8    Object "/umd2_ws/install/umd_utils/lib/libumd_utils.so", at 0x7b03089795eb, in std::__invoke_result<umd_utils::NodeThread::NodeThread(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>)::{lambda()#1}>::type std::__invoke<umd_utils::NodeThread::NodeThread(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>)::{lambda()#1}>(umd_utils::NodeThread::NodeThread(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>)::{lambda()#1}&&)
#7    Object "/umd2_ws/install/umd_utils/lib/libumd_utils.so", at 0x7b0308979665, in void std::__invoke_impl<void, umd_utils::NodeThread::NodeThread(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>)::{lambda()#1}>(std::__invoke_other, umd_utils::NodeThread::NodeThread(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>)::{lambda()#1}&&)
#6    Object "/umd2_ws/install/umd_utils/lib/libumd_utils.so", at 0x7b0308978ab0, in umd_utils::NodeThread::NodeThread(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>)::{lambda()#1}::operator()() const
#5    Object "/opt/ros/humble/lib/librclcpp.so", at 0x7b0308a89970, in rclcpp::executors::SingleThreadedExecutor::spin()
#4    Object "/opt/ros/humble/lib/librclcpp.so", at 0x7b0308a82492, in rclcpp::Executor::get_next_executable(rclcpp::AnyExecutable&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >)
#3    Object "/opt/ros/humble/lib/librclcpp.so", at 0x7b0308a7f70b, in rclcpp::Executor::wait_for_work(std::chrono::duration<long, std::ratio<1l, 1000000000l> >)
#2    Object "/opt/ros/humble/lib/librcl.so", at 0x7b0308353847, in rcl_wait
#1    Object "/opt/ros/humble/lib/librmw_cyclonedds_cpp.so", at 0x7b0307dfe87a, in rmw_wait
#0    Object "/opt/ros/humble/lib/librmw_cyclonedds_cpp.so", at 0x7b0307dfc396, in
Segmentation fault (Signal sent by the kernel [(nil)])
[ros2run]: Segmentation fault

Additional information


Feature request

Feature description

Implementation considerations

stevedanomodolor commented 2 days ago

I get a segfault here image