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

fix modules coredump due to data race in shm_manager #87

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open

fix modules coredump due to data race in shm_manager #87

wants to merge 1 commit into from

Conversation

csstormq
Copy link

@csstormq csstormq commented Jul 3, 2019

  • 问题现象

localization模块由于异常导致进程崩溃,其所产生coredump堆栈信息为:

(gdb) bt full
#0  0x00000000004f5200 in boost::detail::shared_count::~shared_count (this=0x8, __in_chrg=<optimized out>) at /usr/include/boost/smart_ptr/detail/shared_count.hpp:371
No locals.
#1  0x0000007fb5af3c0c in boost::shared_ptr<ros::PublisherLink>::~shared_ptr (this=0x0, __in_chrg=<optimized out>) at /usr/include/boost/smart_ptr/shared_ptr.hpp:328
No locals.
#2  0x0000007fb5bdc8f0 in std::_Destroy<boost::shared_ptr<ros::PublisherLink> > (__pointer=0x0) at /usr/include/c++/4.8/bits/stl_construct.h:93
No locals.
#3  0x0000007fb5bdb0e0 in std::_Destroy_aux<false>::__destroy<boost::shared_ptr<ros::PublisherLink>*> (__first=0x0, __last=0x10) at /usr/include/c++/4.8/bits/stl_construct.h:103
No locals.
#4  0x0000007fb5bd8d60 in std::_Destroy<boost::shared_ptr<ros::PublisherLink>*> (__first=0x0, __last=0x10) at /usr/include/c++/4.8/bits/stl_construct.h:126
No locals.
#5  0x0000007fb5bd6b8c in std::_Destroy<boost::shared_ptr<ros::PublisherLink>*, boost::shared_ptr<ros::PublisherLink> > (__first=0x0, __last=0x10)
    at /usr/include/c++/4.8/bits/stl_construct.h:151
No locals.
#6  0x0000007fb5bd4790 in std::vector<boost::shared_ptr<ros::PublisherLink>, std::allocator<boost::shared_ptr<ros::PublisherLink> > >::~vector (this=0x7fa67fe4c8, 
    __in_chrg=<optimized out>) at /usr/include/c++/4.8/bits/stl_vector.h:415
No locals.
#7  0x0000007fb5beca3c in ros::ShmManager::threadFunc (this=0x16187e0) at /apollo/package/apollo-platform-master/ros/ros_comm/roscpp/src/libros/shm_manager.cpp:139
        segment = 0x0
        descriptors_sub = 0x7f88001598
        segment_mgr = 0x0
        queue_size = 0
        lock = {m = 0x7fa67fe4a8, is_locked = true}
        subs = {<std::_List_base<boost::shared_ptr<ros::Subscription>, std::allocator<boost::shared_ptr<ros::Subscription> > >> = {
            _M_impl = {<std::allocator<std::_List_node<boost::shared_ptr<ros::Subscription> > >> = {<__gnu_cxx::new_allocator<std::_List_node<boost::shared_ptr<ros::Subscription> > >> = {<No data fields>}, <No data fields>}, _M_node = {_M_next = 0x7f88000980, _M_prev = 0x7f88000920}}}, <No data fields>}
        it = {_M_node = 0x7f88000980}
        sharedmem_util = {_vptr.SharedMemoryUtil = 0x7fb5fac0e0 <vtable for sharedmem_transport::SharedMemoryUtil+16>}
        topic = {static npos = <optimized out>, _M_dataplus = {<std::allocator<char>> = {<__gnu_cxx::new_allocator<char>> = {<No data fields>}, <No data fields>}, 
            _M_p = 0x7f88001998 "/odom"}}
        __PRETTY_FUNCTION__ = "void ros::ShmManager::threadFunc()"
#8  0x0000007fb5bebcd4 in ros::ShmManager::__lambda0::operator() (__closure=0x1095300) at /apollo/package/apollo-platform-master/ros/ros_comm/roscpp/src/libros/shm_manager.cpp:75
        this = 0x16187e0
#9  0x0000007fb5bef3ec in std::_Bind_simple<ros::ShmManager::start()::__lambda0()>::_M_invoke<>(std::_Index_tuple<>) (this=0x1095300) at /usr/include/c++/4.8/functional:1732
No locals.
#10 0x0000007fb5bef29c in std::_Bind_simple<ros::ShmManager::start()::__lambda0()>::operator()(void) (this=0x1095300) at /usr/include/c++/4.8/functional:1720
No locals.
#11 0x0000007fb5bef1d4 in std::thread::_Impl<std::_Bind_simple<ros::ShmManager::start()::__lambda0()> >::_M_run(void) (this=0x10952e8) at /usr/include/c++/4.8/thread:115
No locals.
#12 0x0000007fb5335280 in ?? () from /usr/lib/aarch64-linux-gnu/libstdc++.so.6
No symbol table info available.
#13 0x0000007fb5209e48 in start_thread (arg=0x7fa67fef10) at pthread_create.c:314
        pd = 0x7fa67fef10
        unwind_buf = {cancel_jmp_buf = {{jmp_buf = {548254248720, 548880678536, 548499783680, 0, 548499779584, 548254248912, 548254246944, 548399691504, 8388608, 548499800064, 
                548254246656, 12911323298571427958, 0, 12911323298793281898, 0, 0, 0, 0, 0, 0, 0, 0}, mask_was_saved = 0}}, priv = {pad = {0x0, 0x0, 0x7fb5209d9c <start_thread>, 
              0x7fa67fef10}, data = {prev = 0x0, cleanup = 0x0, canceltype = -1256153700}}}
        not_first_call = 0
        pagesize_m1 = <optimized out>
        sp = <optimized out>
        freesize = <optimized out>
        __PRETTY_FUNCTION__ = "start_thread"
#14 0x0000007fb5020320 in clone () at ../ports/sysdeps/unix/sysv/linux/aarch64/nptl/../clone.S:96
No locals.
(gdb) 
  • 原因分析

    调用get_publisher_links()函数时,会调用std::vector的拷贝构造函数,将publisher_links_中的元素拷贝到临时对象中。该函数的可能执行步骤为:1)调用std::vector基类的构造函数——即_Base(__x.size()),如果此时publisher_links_的元素数量为0,那么基类会将_M_start、M_finish和_M_end_of_storage都初始化为0;2)基类构造函数执行完后,会调用stl_vector.h:313行的代码对publisher_links_中的元素进行拷贝操作,如果在调用之前publisher_links_新增了一个元素,那么publisher_links.M_start和publisher_links._M_finish的值会得到更新,并且它们之间的差是0x10(通过sizeof函数可以得出publisher_links_中一个元素占用16字节的存储空间)。那么当调用std::__uninitialized_copy_a()函数时,会构建一个类型为boost::shared_ptr的元素,并返回__cur(值为0x10)赋值给临时对象的数据成员_M_finish。3)临时对象析构时,会释放内存地址从_M_start(值为0x0)到_M_finish(值为0x10)的内存,从而导致localization模块进程崩溃。此执行顺序的可能性通过gdb调试测试程序时也得到了验证,可以得到与localization模块几乎完全相同的coredump,具体调试过程见“gdb调试测试程序”。

  • gdb调试测试程序

nvidia@in_dev_docker:/apollo/localization_sim$ gdb main
GNU gdb (Ubuntu 7.7.1-0ubuntu5~14.04.3) 7.7.1
Copyright (C) 2014 Free Software Foundation, Inc.
License GPLv3+: GNU GPL version 3 or later <http://gnu.org/licenses/gpl.html>
This is free software: you are free to change and redistribute it.
There is NO WARRANTY, to the extent permitted by law.  Type "show copying"
and "show warranty" for details.
This GDB was configured as "aarch64-linux-gnu".
Type "show configuration" for configuration details.
For bug reporting instructions, please see:
<http://www.gnu.org/software/gdb/bugs/>.
Find the GDB manual and other documentation resources online at:
<http://www.gnu.org/software/gdb/documentation/>.
For help, type "help".
Type "apropos word" to search for commands related to "word"...
Reading symbols from main...done.
(gdb) directory  /usr/include/c++/4.8/bits/
Source directories searched: /usr/include/c++/4.8/bits:$cdir:$cwd
(gdb) start
Temporary breakpoint 1 at 0x400fc8: file main.cpp, line 6.
Starting program: /apollo/localization_sim/main 
[Thread debugging using libthread_db enabled]
Using host libthread_db library "/lib/aarch64-linux-gnu/libthread_db.so.1".

Temporary breakpoint 1, main () at main.cpp:6
6	    TopicManager::instance();
(gdb) set listsize 30
(gdb) b main.cpp:12
Breakpoint 2 at 0x400fd8: file main.cpp, line 12.
(gdb) l main.cpp:12
1	#include "shm_manager_sim.h"
2	#include "topic_manager_sim.h"
3	
4	int main()
5	{
6	    TopicManager::instance();
7	    
8	    ShmManager::instance()->start();
9	
10	    while(true)
11	    {
12	        TopicManager::instance()->subscribe();
13	        std::this_thread::sleep_for(std::chrono::duration<double, std::milli>(10));
14	        if (TopicManager::instance()->getNumSubscriptions() > 1000)
15	        {
16	            TopicManager::instance()->shutdown();
17	        }
18	    }
19	    
20	    return 0;
21	}
(gdb) c
Continuing.
[New Thread 0x7fb7bee1d0 (LWP 1732)]

Breakpoint 2, main () at main.cpp:12
12	        TopicManager::instance()->subscribe();
(gdb) c
Continuing.

Breakpoint 2, main () at main.cpp:12
12	        TopicManager::instance()->subscribe();
(gdb) b stl_uninitialized.h:75 thread 2
Breakpoint 3 at 0x4041e4: stl_uninitialized.h:75. (2 locations)
(gdb) b stl_uninitialized.h:80 thread 2
Breakpoint 4 at 0x40424c: stl_uninitialized.h:80. (2 locations)
(gdb) c
Continuing.
[Switching to Thread 0x7fb7bee1d0 (LWP 1732)]

Breakpoint 3, std::__uninitialized_copy<false>::__uninit_copy<__gnu_cxx::__normal_iterator<std::shared_ptr<PublisherLink> const*, std::vector<std::shared_ptr<PublisherLink>, std::allocator<std::shared_ptr<PublisherLink> > > >, std::shared_ptr<PublisherLink>*> (__first=..., __last=..., __result=0x7fb00008f0) at /usr/include/c++/4.8/bits/stl_uninitialized.h:75
75			std::_Construct(std::__addressof(*__cur), *__first);
(gdb) c
Continuing.
[Switching to Thread 0x7fb7ff8000 (LWP 1415)]

Breakpoint 2, main () at main.cpp:12
12	        TopicManager::instance()->subscribe();
(gdb) c
Continuing.
[Switching to Thread 0x7fb7bee1d0 (LWP 1732)]

Breakpoint 3, std::__uninitialized_copy<false>::__uninit_copy<__gnu_cxx::__normal_iterator<std::shared_ptr<PublisherLink> const*, std::vector<std::shared_ptr<PublisherLink>, std::allocator<std::shared_ptr<PublisherLink> > > >, std::shared_ptr<PublisherLink>*> (__first=..., __last=..., __result=0x7fb00008f0) at /usr/include/c++/4.8/bits/stl_uninitialized.h:75
75			std::_Construct(std::__addressof(*__cur), *__first);
(gdb) i args
__first = {_M_current = 0x42fee0}
__last = {_M_current = 0x42fef0}
__result = 0x7fb00008f0
(gdb) i locals
__cur = 0x7fb00008f0
(gdb) set __cur=0x0
(gdb) i args
__first = {_M_current = 0x42fee0}
__last = {_M_current = 0x42fef0}
__result = 0x7fb00008f0
(gdb) i locals
__cur = 0x0
(gdb) l
60	{
61	_GLIBCXX_BEGIN_NAMESPACE_VERSION
62	
63	  template<bool _TrivialValueTypes>
64	    struct __uninitialized_copy
65	    {
66	      template<typename _InputIterator, typename _ForwardIterator>
67	        static _ForwardIterator
68	        __uninit_copy(_InputIterator __first, _InputIterator __last,
69			      _ForwardIterator __result)
70	        {
71		  _ForwardIterator __cur = __result;
72		  __try
73		    {
74		      for (; __first != __last; ++__first, ++__cur)
75			std::_Construct(std::__addressof(*__cur), *__first);
76		      return __cur;
77		    }
78		  __catch(...)
79		    {
80		      std::_Destroy(__result, __cur);
81		      __throw_exception_again;
82		    }
83		}
84	    };
85	
86	  template<>
87	    struct __uninitialized_copy<true>
88	    {
89	      template<typename _InputIterator, typename _ForwardIterator>
(gdb) where
#0  std::__uninitialized_copy<false>::__uninit_copy<__gnu_cxx::__normal_iterator<std::shared_ptr<PublisherLink> const*, std::vector<std::shared_ptr<PublisherLink>, std::allocator<std::shared_ptr<PublisherLink> > > >, std::shared_ptr<PublisherLink>*> (__first=..., __last=..., __result=0x7fb00008f0) at /usr/include/c++/4.8/bits/stl_uninitialized.h:75
#1  0x0000000000403f74 in std::uninitialized_copy<__gnu_cxx::__normal_iterator<std::shared_ptr<PublisherLink> const*, std::vector<std::shared_ptr<PublisherLink>, std::allocator<std::shared_ptr<PublisherLink> > > >, std::shared_ptr<PublisherLink>*> (__first=..., __last=..., __result=0x7fb00008f0) at /usr/include/c++/4.8/bits/stl_uninitialized.h:117
#2  0x0000000000403b74 in std::__uninitialized_copy_a<__gnu_cxx::__normal_iterator<std::shared_ptr<PublisherLink> const*, std::vector<std::shared_ptr<PublisherLink>, std::allocator<std::shared_ptr<PublisherLink> > > >, std::shared_ptr<PublisherLink>*, std::shared_ptr<PublisherLink> > (__first=..., __last=..., __result=0x7fb00008f0)
    at /usr/include/c++/4.8/bits/stl_uninitialized.h:258
#3  0x00000000004038e8 in std::vector<std::shared_ptr<PublisherLink>, std::allocator<std::shared_ptr<PublisherLink> > >::vector (this=0x7fb7bed8f8, __x=...)
    at /usr/include/c++/4.8/bits/stl_vector.h:316
#4  0x00000000004037c0 in Subscription::get_publisher_links (this=0x42fe48) at subscription_sim.cpp:5
#5  0x00000000004016c4 in ShmManager::threadFunc (this=0x42fc80) at shm_manager_sim.cpp:42
#6  0x0000000000401600 in ShmManager::__lambda0::operator() (__closure=0x42fcf0) at shm_manager_sim.cpp:28
#7  0x0000000000402604 in std::_Bind_simple<ShmManager::start()::__lambda0()>::_M_invoke<>(std::_Index_tuple<>) (this=0x42fcf0) at /usr/include/c++/4.8/functional:1732
#8  0x000000000040255c in std::_Bind_simple<ShmManager::start()::__lambda0()>::operator()(void) (this=0x42fcf0) at /usr/include/c++/4.8/functional:1720
#9  0x00000000004024f8 in std::thread::_Impl<std::_Bind_simple<ShmManager::start()::__lambda0()> >::_M_run(void) (this=0x42fcd8) at /usr/include/c++/4.8/thread:115
#10 0x0000007fb7ee3280 in ?? () from /usr/lib/aarch64-linux-gnu/libstdc++.so.6
#11 0x0000007fb7de3e48 in start_thread (arg=0x7fb7bee1d0) at pthread_create.c:314
#12 0x0000007fb7d5a320 in clone () at ../ports/sysdeps/unix/sysv/linux/aarch64/nptl/../clone.S:96
(gdb) n
[Switching to Thread 0x7fb7ff8000 (LWP 1415)]

Breakpoint 2, main () at main.cpp:12
12	        TopicManager::instance()->subscribe();
(gdb) thread 2
[Switching to thread 2 (Thread 0x7fb7bee1d0 (LWP 1732))]
#0  std::__uninitialized_copy<false>::__uninit_copy<__gnu_cxx::__normal_iterator<std::shared_ptr<PublisherLink> const*, std::vector<std::shared_ptr<PublisherLink>, std::allocator<std::shared_ptr<PublisherLink> > > >, std::shared_ptr<PublisherLink>*> (__first=..., __last=..., __result=0x7fb00008f0) at /usr/include/c++/4.8/bits/stl_uninitialized.h:74
74		      for (; __first != __last; ++__first, ++__cur)
(gdb) n
76		      return __cur;
(gdb) i locals
__cur = 0x10
(gdb) i args
__first = {_M_current = 0x42fef0}
__last = {_M_current = 0x42fef0}
__result = 0x7fb00008f0
(gdb) thread 2
[Switching to thread 2 (Thread 0x7fb7bee1d0 (LWP 1732))]
#0  std::__uninitialized_copy<false>::__uninit_copy<__gnu_cxx::__normal_iterator<std::shared_ptr<PublisherLink> const*, std::vector<std::shared_ptr<PublisherLink>, std::allocator<std::shared_ptr<PublisherLink> > > >, std::shared_ptr<PublisherLink>*> (__first=..., __last=..., __result=0x7fb00008f0) at /usr/include/c++/4.8/bits/stl_uninitialized.h:76
76		      return __cur;
(gdb) n
83		}
(gdb) n
std::uninitialized_copy<__gnu_cxx::__normal_iterator<std::shared_ptr<PublisherLink> const*, std::vector<std::shared_ptr<PublisherLink>, std::allocator<std::shared_ptr<PublisherLink> > > >, std::shared_ptr<PublisherLink>*> (__first=..., __last=..., __result=0x7fb00008f0) at /usr/include/c++/4.8/bits/stl_uninitialized.h:118
118	    }
(gdb) l
103	   *  Like copy(), but does not require an initialized output range.
104	  */
105	  template<typename _InputIterator, typename _ForwardIterator>
106	    inline _ForwardIterator
107	    uninitialized_copy(_InputIterator __first, _InputIterator __last,
108			       _ForwardIterator __result)
109	    {
110	      typedef typename iterator_traits<_InputIterator>::value_type
111		_ValueType1;
112	      typedef typename iterator_traits<_ForwardIterator>::value_type
113		_ValueType2;
114	
115	      return std::__uninitialized_copy<(__is_trivial(_ValueType1)
116						&& __is_trivial(_ValueType2))>::
117		__uninit_copy(__first, __last, __result);
118	    }
119	
120	
121	  template<bool _TrivialValueType>
122	    struct __uninitialized_fill
123	    {
124	      template<typename _ForwardIterator, typename _Tp>
125	        static void
126	        __uninit_fill(_ForwardIterator __first, _ForwardIterator __last,
127			      const _Tp& __x)
128	        {
129		  _ForwardIterator __cur = __first;
130		  __try
131		    {
132		      for (; __cur != __last; ++__cur)
(gdb) n
[Switching to Thread 0x7fb7ff8000 (LWP 1415)]

Breakpoint 2, main () at main.cpp:12
12	        TopicManager::instance()->subscribe();
(gdb) thread 2
[Switching to thread 2 (Thread 0x7fb7bee1d0 (LWP 1732))]
#0  std::uninitialized_copy<__gnu_cxx::__normal_iterator<std::shared_ptr<PublisherLink> const*, std::vector<std::shared_ptr<PublisherLink>, std::allocator<std::shared_ptr<PublisherLink> > > >, std::shared_ptr<PublisherLink>*> (__first=..., __last=..., __result=0x7fb00008f0) at /usr/include/c++/4.8/bits/stl_uninitialized.h:118
118	    }
(gdb) n
std::vector<std::shared_ptr<PublisherLink>, std::allocator<std::shared_ptr<PublisherLink> > >::vector (this=0x7fb7bed8f8, __x=...) at /usr/include/c++/4.8/bits/stl_vector.h:313
313	      { this->_M_impl._M_finish =
(gdb) l
298	      { _M_fill_initialize(__n, __value); }
299	#endif
300	
301	      /**
302	       *  @brief  %Vector copy constructor.
303	       *  @param  __x  A %vector of identical element and allocator types.
304	       *
305	       *  The newly-created %vector uses a copy of the allocation
306	       *  object used by @a __x.  All the elements of @a __x are copied,
307	       *  but any extra memory in
308	       *  @a __x (for fast expansion) will not be copied.
309	       */
310	      vector(const vector& __x)
311	      : _Base(__x.size(),
312	        _Alloc_traits::_S_select_on_copy(__x._M_get_Tp_allocator()))
313	      { this->_M_impl._M_finish =
314		  std::__uninitialized_copy_a(__x.begin(), __x.end(),
315					      this->_M_impl._M_start,
316					      _M_get_Tp_allocator());
317	      }
318	
319	#if __cplusplus >= 201103L
320	      /**
321	       *  @brief  %Vector move constructor.
322	       *  @param  __x  A %vector of identical element and allocator types.
323	       *
324	       *  The newly-created %vector contains the exact contents of @a __x.
325	       *  The contents of @a __x are a valid, but unspecified %vector.
326	       */
327	      vector(vector&& __x) noexcept
(gdb) n
317	      }
(gdb) p this->_M_impl._M_finish
$1 = (std::_Vector_base<std::shared_ptr<PublisherLink>, std::allocator<std::shared_ptr<PublisherLink> > >::pointer) 0x10
(gdb) p this->_M_impl
$2 = {<std::allocator<std::shared_ptr<PublisherLink> >> = {<__gnu_cxx::new_allocator<std::shared_ptr<PublisherLink> >> = {<No data fields>}, <No data fields>}, 
  _M_start = 0x7fb00008f0, _M_finish = 0x10, _M_end_of_storage = 0x7fb0000900}
(gdb) d breakpoints
Delete all breakpoints? (y or n) y
(gdb) b stl_vector.h:415 thread 2
Breakpoint 5 at 0x402c68: file /usr/include/c++/4.8/bits/stl_vector.h, line 415.
(gdb) i breakpoints
Num     Type           Disp Enb Address            What
5       breakpoint     keep y   0x0000000000402c68 in std::vector<std::shared_ptr<PublisherLink>, std::allocator<std::shared_ptr<PublisherLink> > >::"~"vector() 
                                                   at /usr/include/c++/4.8/bits/stl_vector.h:415 thread 2
	stop only in thread 2
(gdb) c
Continuing.

Breakpoint 5, std::vector<std::shared_ptr<PublisherLink>, std::allocator<std::shared_ptr<PublisherLink> > >::~vector (this=0x7fb7bed8f8, __in_chrg=<optimized out>)
    at /usr/include/c++/4.8/bits/stl_vector.h:415
415	      { std::_Destroy(this->_M_impl._M_start, this->_M_impl._M_finish,
(gdb) p this->_M_impl
$3 = {<std::allocator<std::shared_ptr<PublisherLink> >> = {<__gnu_cxx::new_allocator<std::shared_ptr<PublisherLink> >> = {<No data fields>}, <No data fields>}, 
  _M_start = 0x7fb00008f0, _M_finish = 0x10, _M_end_of_storage = 0x7fb0000900}
(gdb) l
400		: _Base(__a)
401	        {
402		  // Check whether it's an integral type.  If so, it's not an iterator.
403		  typedef typename std::__is_integer<_InputIterator>::__type _Integral;
404		  _M_initialize_dispatch(__first, __last, _Integral());
405		}
406	#endif
407	
408	      /**
409	       *  The dtor only erases the elements, and note that if the
410	       *  elements themselves are pointers, the pointed-to memory is
411	       *  not touched in any way.  Managing the pointer is the user's
412	       *  responsibility.
413	       */
414	      ~vector() _GLIBCXX_NOEXCEPT
415	      { std::_Destroy(this->_M_impl._M_start, this->_M_impl._M_finish,
416			      _M_get_Tp_allocator()); }
417	
418	      /**
419	       *  @brief  %Vector assignment operator.
420	       *  @param  __x  A %vector of identical element and allocator types.
421	       *
422	       *  All the elements of @a __x are copied, but any extra memory in
423	       *  @a __x (for fast expansion) will not be copied.  Unlike the
424	       *  copy constructor, the allocator object is not copied.
425	       */
426	      vector&
427	      operator=(const vector& __x);
428	
429	#if __cplusplus >= 201103L
(gdb) si
0x0000000000402c6c	415	      { std::_Destroy(this->_M_impl._M_start, this->_M_impl._M_finish,
(gdb) si
0x0000000000402c70	415	      { std::_Destroy(this->_M_impl._M_start, this->_M_impl._M_finish,
(gdb) si
std::_Destroy<std::shared_ptr<PublisherLink>*, std::shared_ptr<PublisherLink> > (__first=0x7fb7bed8f8, __last=0x7fb7bed8e8) at /usr/include/c++/4.8/bits/stl_construct.h:148
148	    _Destroy(_ForwardIterator __first, _ForwardIterator __last,
(gdb) l
133	   * destroy() even if _Tp has a trivial destructor.
134	   */
135	
136	  template<typename _ForwardIterator, typename _Allocator>
137	    void
138	    _Destroy(_ForwardIterator __first, _ForwardIterator __last,
139		     _Allocator& __alloc)
140	    {
141	      typedef __gnu_cxx::__alloc_traits<_Allocator> __traits;
142	      for (; __first != __last; ++__first)
143		__traits::destroy(__alloc, std::__addressof(*__first));
144	    }
145	
146	  template<typename _ForwardIterator, typename _Tp>
147	    inline void
148	    _Destroy(_ForwardIterator __first, _ForwardIterator __last,
149		     allocator<_Tp>&)
150	    {
151	      _Destroy(__first, __last);
152	    }
153	
154	_GLIBCXX_END_NAMESPACE_VERSION
155	} // namespace std
156	
157	#endif /* _STL_CONSTRUCT_H */
158	
(gdb) n
151	      _Destroy(__first, __last);
(gdb) i args
__first = 0x7fb00008f0
__last = 0x10
(gdb) si
0x0000000000402f08	151	      _Destroy(__first, __last);
(gdb) si
0x0000000000402f0c	151	      _Destroy(__first, __last);
(gdb) si
std::_Destroy<std::shared_ptr<PublisherLink>*> (__first=0x7fb7bee5e8, __last=0x7fb7bed8f8) at /usr/include/c++/4.8/bits/stl_construct.h:122
122	    _Destroy(_ForwardIterator __first, _ForwardIterator __last)
(gdb) si
0x0000000000403208	122	    _Destroy(_ForwardIterator __first, _ForwardIterator __last)
(gdb) si
0x000000000040320c	122	    _Destroy(_ForwardIterator __first, _ForwardIterator __last)
(gdb) si
0x0000000000403210	122	    _Destroy(_ForwardIterator __first, _ForwardIterator __last)
(gdb) si
126	      std::_Destroy_aux<__has_trivial_destructor(_Value_type)>::
(gdb) si
0x0000000000403218	126	      std::_Destroy_aux<__has_trivial_destructor(_Value_type)>::
(gdb) si
0x000000000040321c	126	      std::_Destroy_aux<__has_trivial_destructor(_Value_type)>::
(gdb) si
std::_Destroy_aux<false>::__destroy<std::shared_ptr<PublisherLink>*> (__first=0x42fee0, __last=0x42fef0) at /usr/include/c++/4.8/bits/stl_construct.h:100
100	        __destroy(_ForwardIterator __first, _ForwardIterator __last)
(gdb) l
85	#endif
86	
87	  /**
88	   * Destroy the object pointed to by a pointer type.
89	   */
90	  template<typename _Tp>
91	    inline void
92	    _Destroy(_Tp* __pointer)
93	    { __pointer->~_Tp(); }
94	
95	  template<bool>
96	    struct _Destroy_aux
97	    {
98	      template<typename _ForwardIterator>
99	        static void
100	        __destroy(_ForwardIterator __first, _ForwardIterator __last)
101		{
102		  for (; __first != __last; ++__first)
103		    std::_Destroy(std::__addressof(*__first));
104		}
105	    };
106	
107	  template<>
108	    struct _Destroy_aux<true>
109	    {
110	      template<typename _ForwardIterator>
111	        static void
112	        __destroy(_ForwardIterator, _ForwardIterator) { }
113	    };
114	
(gdb) b stl_construct.h:102 thread 2
Breakpoint 6 at 0x403338: file /usr/include/c++/4.8/bits/stl_construct.h, line 102.
(gdb) n

Breakpoint 6, std::_Destroy_aux<false>::__destroy<std::shared_ptr<PublisherLink>*> (__first=0x7fb00008f0, __last=0x10) at /usr/include/c++/4.8/bits/stl_construct.h:102
102		  for (; __first != __last; ++__first)
(gdb) i args
__first = 0x7fb00008f0
__last = 0x10
(gdb) set __first=0x0
(gdb) i args         
__first = 0x0
__last = 0x10
(gdb) where
#0  std::_Destroy_aux<false>::__destroy<std::shared_ptr<PublisherLink>*> (__first=0x0, __last=0x10) at /usr/include/c++/4.8/bits/stl_construct.h:102
#1  0x0000000000403220 in std::_Destroy<std::shared_ptr<PublisherLink>*> (__first=0x7fb00008f0, __last=0x10) at /usr/include/c++/4.8/bits/stl_construct.h:126
#2  0x0000000000402f10 in std::_Destroy<std::shared_ptr<PublisherLink>*, std::shared_ptr<PublisherLink> > (__first=0x7fb00008f0, __last=0x10)
    at /usr/include/c++/4.8/bits/stl_construct.h:151
#3  0x0000000000402c74 in std::vector<std::shared_ptr<PublisherLink>, std::allocator<std::shared_ptr<PublisherLink> > >::~vector (this=0x7fb7bed8f8, __in_chrg=<optimized out>)
    at /usr/include/c++/4.8/bits/stl_vector.h:415
#4  0x00000000004016e0 in ShmManager::threadFunc (this=0x42fc80) at shm_manager_sim.cpp:42
#5  0x0000000000401600 in ShmManager::__lambda0::operator() (__closure=0x42fcf0) at shm_manager_sim.cpp:28
#6  0x0000000000402604 in std::_Bind_simple<ShmManager::start()::__lambda0()>::_M_invoke<>(std::_Index_tuple<>) (this=0x42fcf0) at /usr/include/c++/4.8/functional:1732
#7  0x000000000040255c in std::_Bind_simple<ShmManager::start()::__lambda0()>::operator()(void) (this=0x42fcf0) at /usr/include/c++/4.8/functional:1720
#8  0x00000000004024f8 in std::thread::_Impl<std::_Bind_simple<ShmManager::start()::__lambda0()> >::_M_run(void) (this=0x42fcd8) at /usr/include/c++/4.8/thread:115
#9  0x0000007fb7ee3280 in ?? () from /usr/lib/aarch64-linux-gnu/libstdc++.so.6
#10 0x0000007fb7de3e48 in start_thread (arg=0x7fb7bee1d0) at pthread_create.c:314
#11 0x0000007fb7d5a320 in clone () at ../ports/sysdeps/unix/sysv/linux/aarch64/nptl/../clone.S:96
(gdb) n
103		    std::_Destroy(std::__addressof(*__first));
(gdb) i args
__first = 0x0
__last = 0x10
(gdb) n

Program received signal SIGSEGV, Segmentation fault.
0x0000000000402a40 in std::__shared_count<(__gnu_cxx::_Lock_policy)2>::~__shared_count (this=0x8, __in_chrg=<optimized out>) at /usr/include/c++/4.8/bits/shared_ptr_base.h:545
545		if (_M_pi != nullptr)
(gdb) p _M_pi
Cannot access memory at address 0x8
(gdb) bt full
#0  0x0000000000402a40 in std::__shared_count<(__gnu_cxx::_Lock_policy)2>::~__shared_count (this=0x8, __in_chrg=<optimized out>) at /usr/include/c++/4.8/bits/shared_ptr_base.h:545
No locals.
#1  0x00000000004033f4 in std::__shared_ptr<PublisherLink, (__gnu_cxx::_Lock_policy)2>::~__shared_ptr (this=0x0, __in_chrg=<optimized out>)
    at /usr/include/c++/4.8/bits/shared_ptr_base.h:781
No locals.
#2  0x0000000000403410 in std::shared_ptr<PublisherLink>::~shared_ptr (this=0x0, __in_chrg=<optimized out>) at /usr/include/c++/4.8/bits/shared_ptr.h:93
No locals.
#3  0x000000000040342c in std::_Destroy<std::shared_ptr<PublisherLink> > (__pointer=0x0) at /usr/include/c++/4.8/bits/stl_construct.h:93
No locals.
#4  0x0000000000403348 in std::_Destroy_aux<false>::__destroy<std::shared_ptr<PublisherLink>*> (__first=0x0, __last=0x10) at /usr/include/c++/4.8/bits/stl_construct.h:103
No locals.
#5  0x0000000000403220 in std::_Destroy<std::shared_ptr<PublisherLink>*> (__first=0x7fb00008f0, __last=0x10) at /usr/include/c++/4.8/bits/stl_construct.h:126
No locals.
#6  0x0000000000402f10 in std::_Destroy<std::shared_ptr<PublisherLink>*, std::shared_ptr<PublisherLink> > (__first=0x7fb00008f0, __last=0x10)
    at /usr/include/c++/4.8/bits/stl_construct.h:151
No locals.
#7  0x0000000000402c74 in std::vector<std::shared_ptr<PublisherLink>, std::allocator<std::shared_ptr<PublisherLink> > >::~vector (this=0x7fb7bed8f8, __in_chrg=<optimized out>)
    at /usr/include/c++/4.8/bits/stl_vector.h:415
No locals.
#8  0x00000000004016e0 in ShmManager::threadFunc (this=0x42fc80) at shm_manager_sim.cpp:42
        subs = {<std::_List_base<std::shared_ptr<Subscription>, std::allocator<std::shared_ptr<Subscription> > >> = {
            _M_impl = {<std::allocator<std::_List_node<std::shared_ptr<Subscription> > >> = {<__gnu_cxx::new_allocator<std::_List_node<std::shared_ptr<Subscription> > >> = {<No data fields>}, <No data fields>}, _M_node = {_M_next = 0x7fb00008c0, _M_prev = 0x7fb0000940}}}, <No data fields>}
        it = {_M_node = 0x7fb00008c0}
#9  0x0000000000401600 in ShmManager::__lambda0::operator() (__closure=0x42fcf0) at shm_manager_sim.cpp:28
        this = 0x42fc80
#10 0x0000000000402604 in std::_Bind_simple<ShmManager::start()::__lambda0()>::_M_invoke<>(std::_Index_tuple<>) (this=0x42fcf0) at /usr/include/c++/4.8/functional:1732
No locals.
#11 0x000000000040255c in std::_Bind_simple<ShmManager::start()::__lambda0()>::operator()(void) (this=0x42fcf0) at /usr/include/c++/4.8/functional:1720
No locals.
#12 0x00000000004024f8 in std::thread::_Impl<std::_Bind_simple<ShmManager::start()::__lambda0()> >::_M_run(void) (this=0x42fcd8) at /usr/include/c++/4.8/thread:115
No locals.
#13 0x0000007fb7ee3280 in ?? () from /usr/lib/aarch64-linux-gnu/libstdc++.so.6
No symbol table info available.
#14 0x0000007fb7de3e48 in start_thread (arg=0x7fb7bee1d0) at pthread_create.c:314
        pd = 0x7fb7bee1d0
        unwind_buf = {cancel_jmp_buf = {{jmp_buf = {548543586768, 549755809512, 548545765376, 0, 548545761280, 548543586960, 548543584992, 548547823344, 8388608, 548545782432, 
                548543584704, 8782422980166335296, 0, 8782422980172602524, 0, 0, 0, 0, 0, 0, 0, 0}, mask_was_saved = 0}}, priv = {pad = {0x0, 0x0, 0x7fb7de3d9c <start_thread>, 
              0x7fb7bee1d0}, data = {prev = 0x0, cleanup = 0x0, canceltype = -1210172004}}}
        not_first_call = 0
        pagesize_m1 = <optimized out>
        sp = <optimized out>
        freesize = <optimized out>
        __PRETTY_FUNCTION__ = "start_thread"
#15 0x0000007fb7d5a320 in clone () at ../ports/sysdeps/unix/sysv/linux/aarch64/nptl/../clone.S:96
No locals.
(gdb) 
  • 测试程序

main.cpp:

#include "shm_manager_sim.h"
#include "topic_manager_sim.h"

int main()
{
    TopicManager::instance();

    ShmManager::instance()->start();

    while(true)
    {
        TopicManager::instance()->subscribe();
        std::this_thread::sleep_for(std::chrono::duration<double, std::milli>(10));
        if (TopicManager::instance()->getNumSubscriptions() > 1000)
        {
            TopicManager::instance()->shutdown();
        }
    }
    
    return 0;
}

shm_manager_sim.h:

#ifndef ROS_SHM_MANAGER_H
#define ROS_SHM_MANAGER_H

#include <memory>
#include <thread>

class ShmManager;
typedef std::shared_ptr<ShmManager> ShmManagerPtr;

class ShmManager
{
public:
    static const ShmManagerPtr& instance();
    void start();
private:
    void threadFunc();
private:
    std::thread server_thread_;
};

#endif  // ROS_SHM_MANAGER_H

shm_manager_sim.cpp:

#include "shm_manager_sim.h"
#include "topic_manager_sim.h"
#include "subscription_sim.h"

#include <mutex>

ShmManagerPtr g_shm_manager;
std::mutex g_shm_manager_mutex;

const ShmManagerPtr& ShmManager::instance() 
{
    if (!g_shm_manager)
    {
        std::lock_guard<std::mutex> lg(g_shm_manager_mutex);

        if (!g_shm_manager)
        {
            g_shm_manager.reset(new ShmManager);
        }
    }
    return g_shm_manager;
}

void ShmManager::start()
{
    server_thread_ = std::thread([this]()
    {
        this->threadFunc();
    });
}

void ShmManager::threadFunc()
{
    while(true)
    {
        if (TopicManager::instance()->getNumSubscriptions() > 0)
        {
            L_Subscription subs = TopicManager::instance()->getAllSubscription();
            L_Subscription::iterator it;
            for (it = subs.begin(); it != subs.end(); ++it) 
            {
                if ((*it)->get_publisher_links().size() == 0)
                {
                    continue;
                }
            }
        }

        std::this_thread::sleep_for(std::chrono::duration<double, std::milli>(10));
    }
}

topic_manager_sim.h:

#ifndef ROSCPP_TOPIC_MANAGER_H
#define ROSCPP_TOPIC_MANAGER_H

#include <memory>
#include <mutex>
#include <list>

class Subscription;
typedef std::shared_ptr<Subscription> SubscriptionPtr;
typedef std::list<SubscriptionPtr> L_Subscription;

class TopicManager;
typedef std::shared_ptr<TopicManager> TopicManagerPtr;

class TopicManager
{
public:
    static const TopicManagerPtr& instance();
    bool subscribe();
    size_t getNumSubscriptions();
    L_Subscription getAllSubscription();
    void shutdown();
private:
    std::mutex subs_mutex_;
    L_Subscription subscriptions_;    
};

#endif // ROSCPP_TOPIC_MANAGER_H

topic_manager_sim.cpp:

#include "topic_manager_sim.h"
#include "subscription_sim.h"

L_Subscription getAllSubscription();

TopicManagerPtr g_topic_manager;
std::mutex g_topic_manager_mutex;
const TopicManagerPtr& TopicManager::instance()
{
    if (!g_topic_manager)
    {
        std::lock_guard<std::mutex> lock(g_topic_manager_mutex);
        if (!g_topic_manager)
        {
           std::lock_guard<std::mutex> lock(g_topic_manager_mutex);
           if (!g_topic_manager)
           {
               g_topic_manager = std::make_shared<TopicManager>();
           }
        }
   }

    return g_topic_manager;
}

bool TopicManager::subscribe()
{
    {
        SubscriptionPtr s(std::make_shared<Subscription>());
        std::lock_guard<std::mutex> lock(subs_mutex_);
        // for (int i = 0; i < 10; ++i)
        {
            s->addPublisherLink();
        }
        subscriptions_.push_back(s);
    }

    return true;
}

size_t TopicManager::getNumSubscriptions()
{
    std::lock_guard<std::mutex> lock(subs_mutex_);
    return subscriptions_.size();
}

L_Subscription TopicManager::getAllSubscription()
{
    return subscriptions_;
}

L_Subscription TopicManager::getAllSubscriptionWithLock()
{
    std::lock_guard<std::mutex> lock(subs_mutex_);
    return subscriptions_;
}

void TopicManager::shutdown()
{
    std::lock_guard<std::mutex> lock(subs_mutex_);
    subscriptions_.clear();
}

subscription_sim.h:

#ifndef ROSCPP_SUBSCRIPTION_H
#define ROSCPP_SUBSCRIPTION_H

#include <memory>
#include <vector>
#include <mutex>

class PublisherLink;
typedef std::shared_ptr<PublisherLink> PublisherLinkPtr;
typedef std::vector<PublisherLinkPtr> V_PublisherLink;

class Subscription : public std::enable_shared_from_this<Subscription>
{
public:
    std::vector<PublisherLinkPtr> get_publisher_links();
    void addPublisherLink();
private:
    V_PublisherLink publisher_links_;
    std::mutex publisher_links_mutex_;
};

class PublisherLink
{
    int i;
    char str[6];
};

#endif  // ROSCPP_SUBSCRIPTION_H

subscription_sim.cpp:

#include "subscription_sim.h"

std::vector<PublisherLinkPtr> Subscription::get_publisher_links()
{
    return publisher_links_;
}

void Subscription::addPublisherLink()
{
    PublisherLinkPtr link = std::make_shared<PublisherLink>();
    std::lock_guard<std::mutex> lock(publisher_links_mutex_);
    publisher_links_.push_back(link);
}

README.md:

###how to compile

$ g++ -std=c++11 -pthread main.cpp shm_manager_sim.cpp subscription_sim.cpp topic_manager_sim.cpp -g  -o main

@CLAassistant
Copy link

CLAassistant commented Jul 3, 2019

CLA assistant check
All committers have signed the CLA.

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.

3 participants