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

An rcl_event_t might be destroyed while a waitset is still using it #760

Closed
ivanpauno opened this issue Apr 7, 2021 · 3 comments · Fixed by #761
Closed

An rcl_event_t might be destroyed while a waitset is still using it #760

ivanpauno opened this issue Apr 7, 2021 · 3 comments · Fixed by #761
Assignees
Labels
bug Something isn't working
Projects

Comments

@ivanpauno
Copy link
Member

Bug report

Required Info:

Steps to reproduce issue

ros2 run rqt_gui rqt_gui

Go to Plugins->Logging->Console
Close the console plugin.

Expected behavior

No segfault.

Actual behavior

The spinning thread segfaults after this line.

Segfaulting thread traceback
#0  0x00007f491c43627f in handle_active_events(rmw_events_t*) () from /home/ivanpauno/ros2_ws/install/rmw_cyclonedds_cpp/lib/librmw_cyclonedds_cpp.so
#1  0x00007f491c437014 in rmw_wait () from /home/ivanpauno/ros2_ws/install/rmw_cyclonedds_cpp/lib/librmw_cyclonedds_cpp.so
#2  0x00007f49261038f1 in rcl_wait () from /home/ivanpauno/ros2_ws/install/rcl/lib/librcl.so
#3  0x00007f4926223614 in rclpy::wait(pybind11::capsule, long) () from /home/ivanpauno/ros2_ws/install/rclpy/lib/python3.8/site-packages/rclpy/_rclpy_pybind11.cpython-38-x86_64-linux-gnu.so
#4  0x00007f49261752f1 in void pybind11::detail::argument_loader<pybind11::capsule, long>::call_impl<void, void (*&)(pybind11::capsule, long), 0ul, 1ul, pybind11::detail::void_type>(void (*&)(pybind11::capsule, long), std::integer_sequence<unsigned long, 0ul, 1ul>, pybind11::detail::void_type&&) && () from /home/ivanpauno/ros2_ws/install/rclpy/lib/python3.8/site-packages/rclpy/_rclpy_pybind11.cpython-38-x86_64-linux-gnu.so
#5  0x00007f492616ec08 in std::enable_if<std::is_void<void>::value, pybind11::detail::void_type>::type pybind11::detail::argument_loader<pybind11::capsule, long>::call<void, pybind11::detail::void_type, void (*&)(pybind11::capsule, long)>(void (*&)(pybind11::capsule, long)) && () from /home/ivanpauno/ros2_ws/install/rclpy/lib/python3.8/site-packages/rclpy/_rclpy_pybind11.cpython-38-x86_64-linux-gnu.so
#6  0x00007f49261ad47a in pybind11::cpp_function::initialize<void (*&)(pybind11::capsule, long), void, pybind11::capsule, long, pybind11::name, pybind11::scope, pybind11::sibling, char [12]>(void (*&)(pybind11::capsule, long), void (*)(pybind11::capsule, long), pybind11::name const&, pybind11::scope const&, pybind11::sibling const&, char const (&) [12])::{lambda(pybind11::detail::function_call&)#3}::operator()(pybind11::detail::function_call&) const () from /home/ivanpauno/ros2_ws/install/rclpy/lib/python3.8/site-packages/rclpy/_rclpy_pybind11.cpython-38-x86_64-linux-gnu.so
#7  0x00007f49261ad516 in pybind11::cpp_function::initialize<void (*&)(pybind11::capsule, long), void, pybind11::capsule, long, pybind11::name, pybind11::scope, pybind11::sibling, char [12]>(void (*&)(pybind11::capsule, long), void (*)(pybind11::capsule, long), pybind11::name const&, pybind11::scope const&, pybind11::sibling const&, char const (&) [12])::{lambda(pybind11::detail::function_call&)#3}::_FUN(pybind11::detail::function_call&) () from /home/ivanpauno/ros2_ws/install/rclpy/lib/python3.8/site-packages/rclpy/_rclpy_pybind11.cpython-38-x86_64-linux-gnu.so
#8  0x00007f4926148ab3 in pybind11::cpp_function::dispatcher(_object*, _object*, _object*) () from /home/ivanpauno/ros2_ws/install/rclpy/lib/python3.8/site-packages/rclpy/_rclpy_pybind11.cpython-38-x86_64-linux-gnu.so
#9  0x00000000005f2fb9 in PyCFunction_Call ()
#10 0x00000000005f3446 in _PyObject_MakeTpCall ()
#11 0x000000000056f600 in _PyEval_EvalFrameDefault ()
#12 0x0000000000500793 in ?? ()
#13 0x00000000004f4f53 in ?? ()
#14 0x00000000005c3cb0 in ?? ()
#15 0x0000000000569f5e in _PyEval_EvalFrameDefault ()
#16 0x000000000056822a in _PyEval_EvalCodeWithName ()
#17 0x00000000005f6033 in _PyFunction_Vectorcall ()
#18 0x000000000056a136 in _PyEval_EvalFrameDefault ()
#19 0x000000000056822a in _PyEval_EvalCodeWithName ()
#20 0x00000000005f6033 in _PyFunction_Vectorcall ()
#21 0x000000000056a136 in _PyEval_EvalFrameDefault ()
#22 0x000000000056822a in _PyEval_EvalCodeWithName ()
#23 0x000000000050a3b0 in ?? ()
#24 0x000000000056b115 in _PyEval_EvalFrameDefault ()
#25 0x00000000005f5e56 in _PyFunction_Vectorcall ()
#26 0x000000000050a33c in ?? ()
#27 0x00000000005f2b87 in PyObject_Call ()
#28 0x00007f4922eed42c in ?? () from /usr/lib/python3/dist-packages/sip.cpython-38-x86_64-linux-gnu.so
#29 0x00007f4922eed513 in ?? () from /usr/lib/python3/dist-packages/sip.cpython-38-x86_64-linux-gnu.so
#30 0x00007f49255a10d6 in ?? () from /usr/lib/python3/dist-packages/PyQt5/QtCore.cpython-38-x86_64-linux-gnu.so
#31 0x00007f4924fec9d2 in ?? () from /lib/x86_64-linux-gnu/libQt5Core.so.5
#32 0x00007f4927103609 in start_thread (arg=<optimized out>) at pthread_create.c:477
#33 0x00007f492723f293 in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95
Other threads traceback (for completeness, nothing worth reading here)
Thread 15 (Thread 0x7f4909057700 (LWP 2790)):                              
#0  futex_wait_cancelable (private=<optimized out>, expected=0, futex_word=0x7f48d4000dc8) at ../sysdeps/nptl/futex-internal.h:183                                      
#1  __pthread_cond_wait_common (abstime=0x0, clockid=0, mutex=0x7f48d4000d78, cond=0x7f48d4000da0) at pthread_cond_wait.c:508                                                          
#2  __pthread_cond_wait (cond=0x7f48d4000da0, mutex=0x7f48d4000d78) at pthread_cond_wait.c:638                                                                                   
#3  0x00007f491c33149d in ddsrt_cond_wait (cond=<optimized out>, mutex=<optimized out>) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/ddsrt/src/sync/posix/sync.c:92
#4  0x00007f491c331565 in ddsrt_cond_waituntil (cond=cond@entry=0x7f48d4000da0, mutex=mutex@entry=0x7f48d4000d78, abstime=abstime@entry=9223372036854775807) at /home/ivanpauno/ros2_ws/src/eclipse-cycloned
ds/cyclonedds/src/ddsrt/src/sync/posix/sync.c:108                         
#5  0x00007f491c31ee2d in dds_waitset_wait_impl (waitset=<optimized out>, xs=0x7f48d4001150, nxs=5, abstimeout=9223372036854775807) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/dd
--Type <RET> for more, q to quit, c to continue without paging--~                                                                                                      
sc/src/dds_waitset.c:79                                                                                                                                                                                     
#6  0x00007f491c429ae4 in discovery_thread(rmw_context_impl_t*) () from /home/ivanpauno/ros2_ws/install/rmw_cyclonedds_cpp/lib/librmw_cyclonedds_cpp.so
#7  0x00007f491c49bf0f in void std::__invoke_impl<void, void (*)(rmw_context_impl_t*), rmw_context_impl_t*>(std::__invoke_other, void (*&&)(rmw_context_impl_t*), rmw_context_impl_t*&&) () from /home/ivanp
auno/ros2_ws/install/rmw_cyclonedds_cpp/lib/librmw_cyclonedds_cpp.so                                                                                                   
#8  0x00007f491c49be5b in std::__invoke_result<void (*)(rmw_context_impl_t*), rmw_context_impl_t*>::type std::__invoke<void (*)(rmw_context_impl_t*), rmw_context_impl_t*>(void (*&&)(rmw_context_impl_t*), 
rmw_context_impl_t*&&) () from /home/ivanpauno/ros2_ws/install/rmw_cyclonedds_cpp/lib/librmw_cyclonedds_cpp.so                                               
#9  0x00007f491c49bdab in void std::thread::_Invoker<std::tuple<void (*)(rmw_context_impl_t*), rmw_context_impl_t*> >::_M_invoke<0ul, 1ul>(std::_Index_tuple<0ul, 1ul>) () from /home/ivanpauno/ros2_ws/inst
all/rmw_cyclonedds_cpp/lib/librmw_cyclonedds_cpp.so                                                                
#10 0x00007f491c49bcd7 in std::thread::_Invoker<std::tuple<void (*)(rmw_context_impl_t*), rmw_context_impl_t*> >::operator()() () from /home/ivanpauno/ros2_ws/install/rmw_cyclonedds_cpp/lib/librmw_cyclone
dds_cpp.so                                                                        
#11 0x00007f491c49bc60 in std::thread::_State_impl<std::thread::_Invoker<std::tuple<void (*)(rmw_context_impl_t*), rmw_context_impl_t*> > >::_M_run() () from /home/ivanpauno/ros2_ws/install/rmw_cyclonedds
_cpp/lib/librmw_cyclonedds_cpp.so                                                                                                                                                      
#12 0x00007f4925a18d84 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6                                                                   
#13 0x00007f4927103609 in start_thread (arg=<optimized out>) at pthread_create.c:477                             
#14 0x00007f492723f293 in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95                                                                                                                          

Thread 14 (Thread 0x7f4909858700 (LWP 2789)):
#0  __libc_recvmsg (flags=0, msg=0x7f4909857600, fd=14) at ../sysdeps/unix/sysv/linux/recvmsg.c:28
#1  __libc_recvmsg (fd=14, msg=msg@entry=0x7f4909857600, flags=flags@entry=0) at ../sysdeps/unix/sysv/linux/recvmsg.c:25
#2  0x00007f491c330bcd in ddsrt_recvmsg (sock=<optimized out>, msg=msg@entry=0x7f4909857600, flags=flags@entry=0, rcvd=rcvd@entry=0x7f49098575e8) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cycloned
ds/src/ddsrt/src/sockets/posix/socket.c:455
#3  0x00007f491c2b0682 in ddsi_udp_conn_read (conn_cmn=0x2e9d500, buf=0x30e8ff0 "", len=65536, allow_spurious=<optimized out>, srcloc=0x7f4909857940) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cycl
onedds/src/core/ddsi/src/ddsi_udp.c:90
#4  0x00007f491c2fdfe3 in ddsi_conn_read (srcloc=0x7f4909857940, allow_spurious=true, len=65536, buf=0x30e8ff0 "", conn=0x2e9d500) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/security
/api/../../core/ddsi/include/dds/ddsi/ddsi_tran.h:254
#5  do_packet (ts1=ts1@entry=0x2eb8a80, gv=gv@entry=0x2ebab98, conn=conn@entry=0x2e9d500, guidprefix=guidprefix@entry=0x0, rbpool=rbpool@entry=0x2ec5a90) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/
cyclonedds/src/core/ddsi/src/q_receive.c:3251
#6  0x00007f491c300f5b in recv_thread (vrecv_thread_arg=<optimized out>) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsi/src/q_receive.c:3499
#7  0x00007f491c301f1b in create_thread_wrapper (ptr=0x2eb8a80) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsi/src/q_thread.c:241
#8  0x00007f491c3317cc in os_startRoutineWrapper (threadContext=0x2ec5ae0) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/ddsrt/src/threads/posix/threads.c:165
#9  0x00007f4927103609 in start_thread (arg=<optimized out>) at pthread_create.c:477
#10 0x00007f492723f293 in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95

Thread 13 (Thread 0x7f490a059700 (LWP 2788)):
#0  __libc_recvmsg (flags=0, msg=0x7f490a058600, fd=16) at ../sysdeps/unix/sysv/linux/recvmsg.c:28
#1  __libc_recvmsg (fd=16, msg=msg@entry=0x7f490a058600, flags=flags@entry=0) at ../sysdeps/unix/sysv/linux/recvmsg.c:25
#2  0x00007f491c330bcd in ddsrt_recvmsg (sock=<optimized out>, msg=msg@entry=0x7f490a058600, flags=flags@entry=0, rcvd=rcvd@entry=0x7f490a0585e8) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cycloned
ds/src/ddsrt/src/sockets/posix/socket.c:455
#3  0x00007f491c2b0682 in ddsi_udp_conn_read (conn_cmn=0x2eaefb0, buf=0x2fe8fb0 "", len=65536, allow_spurious=<optimized out>, srcloc=0x7f490a058940) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cycl
onedds/src/core/ddsi/src/ddsi_udp.c:90
#4  0x00007f491c2fdfe3 in ddsi_conn_read (srcloc=0x7f490a058940, allow_spurious=true, len=65536, buf=0x2fe8fb0 "", conn=0x2eaefb0) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/security
/api/../../core/ddsi/include/dds/ddsi/ddsi_tran.h:254
#5  do_packet (ts1=ts1@entry=0x2eb8a40, gv=gv@entry=0x2ebab98, conn=conn@entry=0x2eaefb0, guidprefix=guidprefix@entry=0x0, rbpool=rbpool@entry=0x2ec5840) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/
cyclonedds/src/core/ddsi/src/q_receive.c:3251
#6  0x00007f491c300f5b in recv_thread (vrecv_thread_arg=<optimized out>) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsi/src/q_receive.c:3499
#7  0x00007f491c301f1b in create_thread_wrapper (ptr=0x2eb8a40) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsi/src/q_thread.c:241
#8  0x00007f491c3317cc in os_startRoutineWrapper (threadContext=0x2ebf9d0) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/ddsrt/src/threads/posix/threads.c:165
#9  0x00007f4927103609 in start_thread (arg=<optimized out>) at pthread_create.c:477
#10 0x00007f492723f293 in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95

Thread 12 (Thread 0x7f490a85a700 (LWP 2787)):
#0  0x00007f492723512b in __GI___select (nfds=19, readfds=0x2e47ff0, writefds=writefds@entry=0x0, exceptfds=0x0, timeout=0x0) at ../sysdeps/unix/sysv/linux/select.c:41
#1  0x00007f491c330d84 in ddsrt_select (nfds=nfds@entry=19, readfds=readfds@entry=0x2e47ff0, writefds=writefds@entry=0x0, errorfds=errorfds@entry=0x0, reltime=reltime@entry=9223372036854775807, ready=read
--Type <RET> for more, q to quit, c to continue without paging--
y@entry=0x7f490a859d94) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/ddsrt/src/sockets/posix/socket.c:557
#2  0x00007f491c301c45 in os_sockWaitsetWait (ws=ws@entry=0x2e47f80) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsi/src/q_sockwaitset.c:864
#3  0x00007f491c30101b in recv_thread (vrecv_thread_arg=<optimized out>) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsi/src/q_receive.c:3552
#4  0x00007f491c301f1b in create_thread_wrapper (ptr=0x2eb8a00) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsi/src/q_thread.c:241
#5  0x00007f491c3317cc in os_startRoutineWrapper (threadContext=0x2ec5600) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/ddsrt/src/threads/posix/threads.c:165
#6  0x00007f4927103609 in start_thread (arg=<optimized out>) at pthread_create.c:477
#7  0x00007f492723f293 in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95

Thread 11 (Thread 0x7f490b05b700 (LWP 2786)):
#0  futex_abstimed_wait_cancelable (private=<optimized out>, abstime=0x7f490b05ad90, clockid=<optimized out>, expected=0, futex_word=0x2eadbec) at ../sysdeps/nptl/futex-internal.h:320
#1  __pthread_cond_wait_common (abstime=0x7f490b05ad90, clockid=<optimized out>, mutex=0x2eadb98, cond=0x2eadbc0) at pthread_cond_wait.c:520
#2  __pthread_cond_timedwait (cond=0x2eadbc0, mutex=0x2eadb98, abstime=0x7f490b05ad90) at pthread_cond_wait.c:656
#3  0x00007f491c331529 in ddsrt_cond_waituntil (cond=<optimized out>, mutex=<optimized out>, abstime=<optimized out>) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/ddsrt/src/sync/posix/
sync.c:116
#4  0x00007f491c3071fb in xevent_thread (xevq=0x2eadb40) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsi/src/q_xevent.c:1288
#5  0x00007f491c301f1b in create_thread_wrapper (ptr=0x2eb89c0) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsi/src/q_thread.c:241
#6  0x00007f491c3317cc in os_startRoutineWrapper (threadContext=0x2e9d3b0) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/ddsrt/src/threads/posix/threads.c:165
#7  0x00007f4927103609 in start_thread (arg=<optimized out>) at pthread_create.c:477
#8  0x00007f492723f293 in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95

Thread 10 (Thread 0x7f4914d23700 (LWP 2785)):
#0  futex_wait_cancelable (private=<optimized out>, expected=0, futex_word=0x7f4918007d40) at ../sysdeps/nptl/futex-internal.h:183
#1  __pthread_cond_wait_common (abstime=0x0, clockid=0, mutex=0x7f4918007cf0, cond=0x7f4918007d18) at pthread_cond_wait.c:508
#2  __pthread_cond_wait (cond=0x7f4918007d18, mutex=0x7f4918007cf0) at pthread_cond_wait.c:638
#3  0x00007f491c33149d in ddsrt_cond_wait (cond=cond@entry=0x7f4918007d18, mutex=mutex@entry=0x7f4918007cf0) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/ddsrt/src/sync/posix/sync.c:92
#4  0x00007f491c2f74ed in dqueue_thread (q=0x7f4918007cf0) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsi/src/q_radmin.c:2533
#5  0x00007f491c301f1b in create_thread_wrapper (ptr=0x2eb8980) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsi/src/q_thread.c:241
#6  0x00007f491c3317cc in os_startRoutineWrapper (threadContext=0x2e9d370) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/ddsrt/src/threads/posix/threads.c:165
#7  0x00007f4927103609 in start_thread (arg=<optimized out>) at pthread_create.c:477
#8  0x00007f492723f293 in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95

Thread 9 (Thread 0x7f4915524700 (LWP 2784)):
#0  futex_wait_cancelable (private=<optimized out>, expected=0, futex_word=0x7f4918008694) at ../sysdeps/nptl/futex-internal.h:183
#1  __pthread_cond_wait_common (abstime=0x0, clockid=0, mutex=0x7f4918008640, cond=0x7f4918008668) at pthread_cond_wait.c:508
#2  __pthread_cond_wait (cond=0x7f4918008668, mutex=0x7f4918008640) at pthread_cond_wait.c:638
#3  0x00007f491c33149d in ddsrt_cond_wait (cond=cond@entry=0x7f4918008668, mutex=mutex@entry=0x7f4918008640) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/ddsrt/src/sync/posix/sync.c:92
#4  0x00007f491c2f74ed in dqueue_thread (q=0x7f4918008640) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsi/src/q_radmin.c:2533
#5  0x00007f491c301f1b in create_thread_wrapper (ptr=0x2eb8940) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsi/src/q_thread.c:241
#6  0x00007f491c3317cc in os_startRoutineWrapper (threadContext=0x2eaf090) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/ddsrt/src/threads/posix/threads.c:165
#7  0x00007f4927103609 in start_thread (arg=<optimized out>) at pthread_create.c:477
#8  0x00007f492723f293 in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95

Thread 8 (Thread 0x7f4915d25700 (LWP 2783)):
#0  futex_abstimed_wait_cancelable (private=<optimized out>, abstime=0x7f4915d24de0, clockid=<optimized out>, expected=0, futex_word=0x2e611e0) at ../sysdeps/nptl/futex-internal.h:320
#1  __pthread_cond_wait_common (abstime=0x7f4915d24de0, clockid=<optimized out>, mutex=0x2e61190, cond=0x2e611b8) at pthread_cond_wait.c:520
#2  __pthread_cond_timedwait (cond=0x2e611b8, mutex=0x2e61190, abstime=0x7f4915d24de0) at pthread_cond_wait.c:656
#3  0x00007f491c331529 in ddsrt_cond_waituntil (cond=<optimized out>, mutex=<optimized out>, abstime=<optimized out>) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/ddsrt/src/sync/posix/
sync.c:116
#4  0x00007f491c2ee5bf in gcreq_queue_thread (q=0x2e61180) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsi/src/q_gc.c:133
#5  0x00007f491c301f1b in create_thread_wrapper (ptr=0x2eb8900) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/core/ddsi/src/q_thread.c:241
#6  0x00007f491c3317cc in os_startRoutineWrapper (threadContext=0x2e9d420) at /home/ivanpauno/ros2_ws/src/eclipse-cyclonedds/cyclonedds/src/ddsrt/src/threads/posix/threads.c:165
--Type <RET> for more, q to quit, c to continue without paging--
#7  0x00007f4927103609 in start_thread (arg=<optimized out>) at pthread_create.c:477
#8  0x00007f492723f293 in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95

Thread 7 (Thread 0x7f49167fc700 (LWP 2782)):
#0  futex_wait_cancelable (private=<optimized out>, expected=0, futex_word=0x263f948) at ../sysdeps/nptl/futex-internal.h:183
#1  __pthread_cond_wait_common (abstime=0x0, clockid=0, mutex=0x263f8f8, cond=0x263f920) at pthread_cond_wait.c:508
#2  __pthread_cond_wait (cond=0x263f920, mutex=0x263f8f8) at pthread_cond_wait.c:638
#3  0x00007f491cca7b5b in ?? () from /usr/lib/x86_64-linux-gnu/dri/iris_dri.so
#4  0x00007f491cca775b in ?? () from /usr/lib/x86_64-linux-gnu/dri/iris_dri.so
#5  0x00007f4927103609 in start_thread (arg=<optimized out>) at pthread_create.c:477
#6  0x00007f492723f293 in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95

Thread 6 (Thread 0x7f4916ffd700 (LWP 2781)):
#0  futex_wait_cancelable (private=<optimized out>, expected=0, futex_word=0x263f948) at ../sysdeps/nptl/futex-internal.h:183
#1  __pthread_cond_wait_common (abstime=0x0, clockid=0, mutex=0x263f8f8, cond=0x263f920) at pthread_cond_wait.c:508
#2  __pthread_cond_wait (cond=0x263f920, mutex=0x263f8f8) at pthread_cond_wait.c:638
#3  0x00007f491cca7b5b in ?? () from /usr/lib/x86_64-linux-gnu/dri/iris_dri.so
#4  0x00007f491cca775b in ?? () from /usr/lib/x86_64-linux-gnu/dri/iris_dri.so
#5  0x00007f4927103609 in start_thread (arg=<optimized out>) at pthread_create.c:477
#6  0x00007f492723f293 in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95

Thread 5 (Thread 0x7f49177fe700 (LWP 2780)):
#0  futex_wait_cancelable (private=<optimized out>, expected=0, futex_word=0x263f948) at ../sysdeps/nptl/futex-internal.h:183
#1  __pthread_cond_wait_common (abstime=0x0, clockid=0, mutex=0x263f8f8, cond=0x263f920) at pthread_cond_wait.c:508
#2  __pthread_cond_wait (cond=0x263f920, mutex=0x263f8f8) at pthread_cond_wait.c:638
#3  0x00007f491cca7b5b in ?? () from /usr/lib/x86_64-linux-gnu/dri/iris_dri.so
#4  0x00007f491cca775b in ?? () from /usr/lib/x86_64-linux-gnu/dri/iris_dri.so
#5  0x00007f4927103609 in start_thread (arg=<optimized out>) at pthread_create.c:477
#6  0x00007f492723f293 in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95

Thread 4 (Thread 0x7f4917fff700 (LWP 2779)):                                                                                                                                                                
#0  futex_wait_cancelable (private=<optimized out>, expected=0, futex_word=0x263f948) at ../sysdeps/nptl/futex-internal.h:183                                                                               
#1  __pthread_cond_wait_common (abstime=0x0, clockid=0, mutex=0x263f8f8, cond=0x263f920) at pthread_cond_wait.c:508                                                                                         
#2  __pthread_cond_wait (cond=0x263f920, mutex=0x263f8f8) at pthread_cond_wait.c:638                                                                                                                        
#3  0x00007f491cca7b5b in ?? () from /usr/lib/x86_64-linux-gnu/dri/iris_dri.so
#4  0x00007f491cca775b in ?? () from /usr/lib/x86_64-linux-gnu/dri/iris_dri.so
#5  0x00007f4927103609 in start_thread (arg=<optimized out>) at pthread_create.c:477
#6  0x00007f492723f293 in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95

Thread 3 (Thread 0x7f491e94b700 (LWP 2777)):
#0  0x00007f4927232aff in __GI___poll (fds=0x7f49100025e0, nfds=1, timeout=-1) at ../sysdeps/unix/sysv/linux/poll.c:29
#1  0x00007f492636e36e in ?? () from /lib/x86_64-linux-gnu/libglib-2.0.so.0
#2  0x00007f492636e4a3 in g_main_context_iteration () from /lib/x86_64-linux-gnu/libglib-2.0.so.0
#3  0x00007f492520c565 in QEventDispatcherGlib::processEvents(QFlags<QEventLoop::ProcessEventsFlag>) () from /lib/x86_64-linux-gnu/libQt5Core.so.5
#4  0x00007f49251b34db in QEventLoop::exec(QFlags<QEventLoop::ProcessEventsFlag>) () from /lib/x86_64-linux-gnu/libQt5Core.so.5
#5  0x00007f4924feb785 in QThread::exec() () from /lib/x86_64-linux-gnu/libQt5Core.so.5
#6  0x00007f492127befa in ?? () from /lib/x86_64-linux-gnu/libQt5DBus.so.5
#7  0x00007f4924fec9d2 in ?? () from /lib/x86_64-linux-gnu/libQt5Core.so.5
#8  0x00007f4927103609 in start_thread (arg=<optimized out>) at pthread_create.c:477
#9  0x00007f492723f293 in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95

Thread 2 (Thread 0x7f491fa53700 (LWP 2776)):
#0  0x00007f4927232aff in __GI___poll (fds=0x7f491fa52d68, nfds=1, timeout=-1) at ../sysdeps/unix/sysv/linux/poll.c:29
--Type <RET> for more, q to quit, c to continue without paging--
#1  0x00007f4922036c1a in ?? () from /lib/x86_64-linux-gnu/libxcb.so.1
#2  0x00007f492203890a in xcb_wait_for_event () from /lib/x86_64-linux-gnu/libxcb.so.1
#3  0x00007f4920241298 in ?? () from /lib/x86_64-linux-gnu/libQt5XcbQpa.so.5
#4  0x00007f4924fec9d2 in ?? () from /lib/x86_64-linux-gnu/libQt5Core.so.5
#5  0x00007f4927103609 in start_thread (arg=<optimized out>) at pthread_create.c:477
#6  0x00007f492723f293 in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95

Thread 1 (Thread 0x7f4926f4f740 (LWP 2774)):                                                                                                                                                         [2/371]
#0  0x00007f4927232aff in __GI___poll (fds=0x7ffe7d0cb1a8, nfds=1, timeout=-1) at ../sysdeps/unix/sysv/linux/poll.c:29                                                                                      
#1  0x00007f4922036c1a in ?? () from /lib/x86_64-linux-gnu/libxcb.so.1                                                                                                                                      
#2  0x00007f4922037329 in ?? () from /lib/x86_64-linux-gnu/libxcb.so.1
#3  0x00007f49220379b0 in xcb_send_request_with_fds64 () from /lib/x86_64-linux-gnu/libxcb.so.1
#4  0x00007f4922037c4d in xcb_send_request () from /lib/x86_64-linux-gnu/libxcb.so.1
#5  0x00007f4922044a1f in xcb_put_image () from /lib/x86_64-linux-gnu/libxcb.so.1
#6  0x00007f491ff53960 in xcb_image_put () from /lib/x86_64-linux-gnu/libxcb-image.so.0
#7  0x00007f4920233d29 in ?? () from /lib/x86_64-linux-gnu/libQt5XcbQpa.so.5
#8  0x00007f492023401b in ?? () from /lib/x86_64-linux-gnu/libQt5XcbQpa.so.5
#9  0x00007f49202344e7 in ?? () from /lib/x86_64-linux-gnu/libQt5XcbQpa.so.5
#10 0x00007f4920234aa0 in ?? () from /lib/x86_64-linux-gnu/libQt5XcbQpa.so.5
#11 0x00007f492280191f in QBackingStore::flush(QRegion const&, QWindow*, QPoint const&) () from /lib/x86_64-linux-gnu/libQt5Gui.so.5
#12 0x00007f4921531f4b in ?? () from /lib/x86_64-linux-gnu/libQt5Widgets.so.5
#13 0x00007f4921533898 in ?? () from /lib/x86_64-linux-gnu/libQt5Widgets.so.5
#14 0x00007f4921534c11 in ?? () from /lib/x86_64-linux-gnu/libQt5Widgets.so.5
#15 0x00007f4921534dc1 in ?? () from /lib/x86_64-linux-gnu/libQt5Widgets.so.5
#16 0x00007f492154d385 in QWidgetPrivate::syncBackingStore() () from /lib/x86_64-linux-gnu/libQt5Widgets.so.5
#17 0x00007f4921565cac in QWidget::event(QEvent*) () from /lib/x86_64-linux-gnu/libQt5Widgets.so.5
#18 0x00007f492167a148 in QMainWindow::event(QEvent*) () from /lib/x86_64-linux-gnu/libQt5Widgets.so.5
#19 0x00007f4921cc619b in ?? () from /usr/lib/python3/dist-packages/PyQt5/QtWidgets.cpython-38-x86_64-linux-gnu.so
#20 0x00007f4921522a66 in QApplicationPrivate::notify_helper(QObject*, QEvent*) () from /lib/x86_64-linux-gnu/libQt5Widgets.so.5
#21 0x00007f492152c0f0 in QApplication::notify(QObject*, QEvent*) () from /lib/x86_64-linux-gnu/libQt5Widgets.so.5
#22 0x00007f4921e29bf6 in ?? () from /usr/lib/python3/dist-packages/PyQt5/QtWidgets.cpython-38-x86_64-linux-gnu.so
#23 0x00007f49251b493a in QCoreApplication::notifyInternal2(QObject*, QEvent*) () from /lib/x86_64-linux-gnu/libQt5Core.so.5
#24 0x00007f49251b75b8 in QCoreApplicationPrivate::sendPostedEvents(QObject*, int, QThreadData*) () from /lib/x86_64-linux-gnu/libQt5Core.so.5
#25 0x00007f492520cf67 in ?? () from /lib/x86_64-linux-gnu/libQt5Core.so.5
#26 0x00007f492636e17d in g_main_context_dispatch () from /lib/x86_64-linux-gnu/libglib-2.0.so.0
#27 0x00007f492636e400 in ?? () from /lib/x86_64-linux-gnu/libglib-2.0.so.0
#28 0x00007f492636e4a3 in g_main_context_iteration () from /lib/x86_64-linux-gnu/libglib-2.0.so.0
#29 0x00007f492520c565 in QEventDispatcherGlib::processEvents(QFlags<QEventLoop::ProcessEventsFlag>) () from /lib/x86_64-linux-gnu/libQt5Core.so.5
#30 0x00007f49251b34db in QEventLoop::exec(QFlags<QEventLoop::ProcessEventsFlag>) () from /lib/x86_64-linux-gnu/libQt5Core.so.5
#31 0x00007f49251bb246 in QCoreApplication::exec() () from /lib/x86_64-linux-gnu/libQt5Core.so.5
#32 0x00007f4921dea9c1 in ?? () from /usr/lib/python3/dist-packages/PyQt5/QtWidgets.cpython-38-x86_64-linux-gnu.so
#33 0x00000000005f305a in PyCFunction_Call ()
#34 0x00000000005f3446 in _PyObject_MakeTpCall ()
#35 0x000000000056f600 in _PyEval_EvalFrameDefault ()
#36 0x000000000056822a in _PyEval_EvalCodeWithName ()
#37 0x000000000050a3b0 in ?? ()
#38 0x000000000056b115 in _PyEval_EvalFrameDefault ()
#39 0x000000000056822a in _PyEval_EvalCodeWithName ()
#40 0x00000000005f6033 in _PyFunction_Vectorcall ()
#41 0x000000000056a136 in _PyEval_EvalFrameDefault ()
#42 0x000000000056822a in _PyEval_EvalCodeWithName ()
#43 0x000000000068c1e7 in PyEval_EvalCode ()
#44 0x000000000067d5a1 in ?? ()
#45 0x000000000067d61f in ?? ()
#46 0x000000000067d6db in PyRun_FileExFlags ()
#47 0x000000000067da6e in PyRun_SimpleFileExFlags ()
#48 0x00000000006b6132 in Py_RunMain ()
#49 0x00000000006b64bd in Py_BytesMain ()
#50 0x00007f49271440b3 in __libc_start_main (main=0x4eec80 <main>, argc=2, argv=0x7ffe7d0cce48, init=<optimized out>, fini=<optimized out>, rtld_fini=<optimized out>, stack_end=0x7ffe7d0cce38) at ../csu/ibc-start.c:308
#51 0x00000000005f927e in _start ()

Additional information

I'm pretty sure that the issue is that we're making sure that subscription handles are alive:

sub_capsules.append(context_stack.enter_context(sub.handle))

but we're not doing something equivalent for waitables.
We could add an enter_context(context) to the waitable interface, though that looks a bit weird.

I also think #757 is needed to solve the issue, though it doesn't completely solve it.

@ivanpauno ivanpauno added the bug Something isn't working label Apr 7, 2021
@ivanpauno ivanpauno added this to To do in Galactic via automation Apr 7, 2021
@ivanpauno
Copy link
Member Author

@sloretz @hidmic opinions?

ros-visualization/rqt_topic#30 is probably also caused by this.
@mjeronimo FYI

@sloretz sloretz self-assigned this Apr 7, 2021
@sloretz
Copy link
Contributor

sloretz commented Apr 7, 2021

Minimal reproducible example:

#!/usr/bin/env python3

import threading
import time

import rclpy
import rclpy.node
import std_msgs.msg


def thread2(node):
    while True:
        sub = node.create_subscription(
            std_msgs.msg.Bool,
            "rclpy_760_mre",
            lambda msg: None,
            10)
        time.sleep(0.01)
        node.destroy_subscription(sub)


def main():
    rclpy.init()
    node = rclpy.node.Node("rclpy_760_mre")

    thread = threading.Thread(target=thread2, args=(node,), daemon=True)
    thread.start()

    rclpy.spin(node)
    rclpy.shutdown()

    thread.join()


if __name__ == '__main__':
    main()

@fujitatomoya
Copy link
Collaborator

confirmed that #761 can fix #760 (comment)

@clalancette clalancette moved this from To do to Reviewer approved in Galactic Apr 8, 2021
@clalancette clalancette moved this from Reviewer approved to Needs Release in Galactic Apr 12, 2021
@clalancette clalancette moved this from Needs Release to Done in Galactic May 23, 2021
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
No open projects
Galactic
  
Done
Development

Successfully merging a pull request may close this issue.

3 participants