Skip to content

Segmentation fault on wait_for_work #1455

@v-lopez

Description

@v-lopez

Bug report

As a workaround for #1454 I tried to create a utility to avoid a hard coded sleep, that blocks until the spin() is active and a callback has been called, before returning.
It causes a segmentation fault very unfrequently.

Required Info:

  • Operating System: Ubuntu 20.04
  • Installation type: Binaries
  • Version or commit hash: 5.0.0-1focal.20201007.211227
  • DDS implementation: Fast DDS
  • Client library (if applicable): rclcpp

Steps to reproduce issue

std::future<void> spin_executor_async(std::shared_ptr<rclcpp::Node> node, rclcpp::Executor &executor)
{
  // We create a timer that will be called as part of the spin
  // this function won't return until the executor is spinning and the timer is called
  std::atomic<bool> timer_called{false};
  std::function<void()> timer_called_lambda = [&](){std::cout << " timer called " << std::endl; timer_called = true;};
  auto timer = node->create_wall_timer(std::chrono::nanoseconds(1), timer_called_lambda);
  executor.add_node(node);
  auto executor_spin_future = std::async(
    std::launch::async, [&executor]() -> void {
      executor.spin();
    });

  while (!timer_called)
  {
    std::this_thread::sleep_for(1ns);
  }
  timer.reset();
  executor.remove_node(node);
  return executor_spin_future;
}

TEST(Foo, bar2) {
  auto node = std::make_shared<rclcpp::Node>("test");
  auto executor = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();

  auto executor_spin_future = spin_executor_async(node, *executor);
  executor->cancel();
  return;
}

Expected behavior

That the test doesn't hang, as a workaround for #1454

Actual behavior

Doesn't hang, but very unfrequently 1% of runs it segfaults.
Because the thread is stuck on executor->spin() (wait_for_work exactly)

Additional information

The segfault happens on thread 2 (the executor spin thread), here's the callstack:

Thread 2 received signal SIGSEGV, Segmentation fault.
[Switching to Thread 9204.9221]
0x00007fc84fcd007b in rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy<std::allocator<void> >::collect_entities(std::map<std::weak_ptr<rclcpp::CallbackGroup>, std::weak_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::owner_less<std::weak_ptr<rclcpp::CallbackGroup> >, std::allocator<std::pair<std::weak_ptr<rclcpp::CallbackGroup> const, std::weak_ptr<rclcpp::node_interfaces::NodeBaseInterface> > > > const&) () from /opt/ros/rolling/lib/librclcpp.so
(rr) bt
#0  0x00007fc84fcd007b in rclcpp::memory_strategies::allocator_memory_strategy::AllocatorMemoryStrategy<std::allocator<void> >::collect_entities(std::map<std::weak_ptr<rclcpp::CallbackGroup>, std::weak_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::owner_less<std::weak_ptr<rclcpp::CallbackGroup> >, std::allocator<std::pair<std::weak_ptr<rclcpp::CallbackGroup> const, std::weak_ptr<rclcpp::node_interfaces::NodeBaseInterface> > > > const&) () from /opt/ros/rolling/lib/librclcpp.so
#1  0x00007fc84fcb93b6 in rclcpp::Executor::wait_for_work(std::chrono::duration<long, std::ratio<1l, 1000000000l> >) () from /opt/ros/rolling/lib/librclcpp.so
#2  0x00007fc84fcb9da3 in rclcpp::Executor::get_next_executable(rclcpp::AnyExecutable&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >) () from /opt/ros/rolling/lib/librclcpp.so
#3  0x00007fc84fcbf00d in rclcpp::executors::SingleThreadedExecutor::spin() () from /opt/ros/rolling/lib/librclcpp.so
#4  0x0000563c231efd7d in <lambda()>::operator()(void) const (__closure=0x563c23c088e8) at /root/control/src/ros2_control/controller_manager/test/test_controller_manager.cpp:143
#5  0x0000563c231f2e13 in std::__invoke_impl<void, spin_executor_async(std::shared_ptr<rclcpp::Node>, rclcpp::Executor&)::<lambda()> >(std::__invoke_other, <lambda()> &&) (__f=...)
    at /usr/include/c++/9/bits/invoke.h:60
#6  0x0000563c231f2db4 in std::__invoke<spin_executor_async(std::shared_ptr<rclcpp::Node>, rclcpp::Executor&)::<lambda()> >(<lambda()> &&) (__fn=...) at /usr/include/c++/9/bits/invoke.h:95
#7  0x0000563c231f2d44 in std::thread::_Invoker<std::tuple<spin_executor_async(std::shared_ptr<rclcpp::Node>, rclcpp::Executor&)::<lambda()> > >::_M_invoke<0>(std::_Index_tuple<0>) (this=0x563c23c088e8)
    at /usr/include/c++/9/thread:244
#8  0x0000563c231f2cd1 in std::thread::_Invoker<std::tuple<spin_executor_async(std::shared_ptr<rclcpp::Node>, rclcpp::Executor&)::<lambda()> > >::operator()(void) (this=0x563c23c088e8)
    at /usr/include/c++/9/thread:251
#9  0x0000563c231f2a74 in std::__future_base::_Task_setter<std::unique_ptr<std::__future_base::_Result<void>, std::__future_base::_Result_base::_Deleter>, std::thread::_Invoker<std::tuple<spin_executor_async(std::shared_ptr<rclcpp::Node>, rclcpp::Executor&)::<lambda()> > >, void>::operator()(void) const (this=0x7fc8496485d0) at /usr/include/c++/9/future:1362
#10 0x0000563c231f2777 in std::_Function_handler<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter>(), std::__future_base::_Task_setter<std::unique_ptr<std::__future_base::_Result<void>, std::__future_base::_Result_base::_Deleter>, std::thread::_Invoker<std::tuple<spin_executor_async(std::shared_ptr<rclcpp::Node>, rclcpp::Executor&)::<lambda()> > >, void> >::_M_invoke(const std::_Any_data &) (__functor=...) at /usr/include/c++/9/bits/std_function.h:286
#11 0x0000563c231f65d0 in std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>::operator()() const (this=0x7fc8496485d0)
    at /usr/include/c++/9/bits/std_function.h:688
#12 0x0000563c231f4ab2 in std::__future_base::_State_baseV2::_M_do_set(std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*) (
    this=0x563c23c088b0, __f=0x7fc8496485d0, __did_set=0x7fc84964852f) at /usr/include/c++/9/future:561
#13 0x0000563c231fcaf5 in std::__invoke_impl<void, void (std::__future_base::_State_baseV2::*)(std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*), std::__future_base::_State_baseV2*, std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*>(std::__invoke_memfun_deref, void (std::__future_base::_State_baseV2::*&&)(std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*), std::__future_base::_State_baseV2*&&, std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*&&, bool*&&) (__f=
    @0x7fc849648570: (void (std::__future_base::_State_baseV2::*)(std::__future_base::_State_baseV2 * const, std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter>()> *, bool *)) 0x563c231f4a78 <std::__future_base::_State_baseV2::_M_do_set(std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*)>, 
    __t=@0x7fc849648540: 0x563c23c088b0) at /usr/include/c++/9/bits/invoke.h:73
#14 0x0000563c231f956e in std::__invoke<void (std::__future_base::_State_baseV2::*)(std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*), std::__future_base::_State_baseV2*, std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*>(void (std::__future_base::_State_baseV2::*&&)(std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*), std::__future_base::_State_baseV2*&&, std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*&&, bool*&&) (__fn=
    @0x7fc849648570: (void (std::__future_base::_State_baseV2::*)(std::__future_base::_State_baseV2 * const, std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter>()> *, bool *)) 0x563c231f4a78 <std::__future_base::_State_baseV2::_M_do_set(std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*)>)
    at /usr/include/c++/9/bits/invoke.h:95
#15 0x0000563c231f6384 in std::call_once<void (std::__future_base::_State_baseV2::*)(std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*), std::__future_base::_State_baseV2*, std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*>(std::once_flag&, void (std::__future_base::_State_baseV2::*&&)(std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*), std::__future_base::_State_baseV2*&&, std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*&&, bool*&&)::{lambda()#1}::operator()() const (this=0x7fc8496484c0) at /usr/include/c++/9/mutex:671
#16 0x0000563c231f63b3 in std::call_once<void (std::__future_base::_State_baseV2::*)(std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*), std::__future_base::_State_baseV2*, std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*>(std::once_flag&, void (std::__future_base::_State_baseV2::*&&)(std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*), std::__future_base::_State_baseV2*&&, std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*&&, bool*&&)::{lambda()#2}::operator()() const (this=0x0) at /usr/include/c++/9/mutex:676
#17 0x0000563c231f63c8 in std::call_once<void (std::__future_base::_State_baseV2::*)(std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*), std::__future_base::_State_baseV2*, std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*>(std::once_flag&, void (std::__future_base::_State_baseV2::*&&)(std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*), std::__future_base::_State_baseV2*&&, std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*&&, bool*&&)::{lambda()#2}::_FUN() () at /usr/include/c++/9/mutex:676
#18 0x00007fc84fbbc47f in __pthread_once_slow (once_control=0x563c23c088c8, init_routine=0x7fc84f771b80 <__once_proxy>) at pthread_once.c:116
#19 0x0000563c231ed57a in __gthread_once (__once=0x563c23c088c8, __func=0x7fc84f771b80 <__once_proxy>) at /usr/include/x86_64-linux-gnu/c++/9/bits/gthr-default.h:700
#20 0x0000563c231f6472 in std::call_once<void (std::__future_base::_State_baseV2::*)(std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*), std::__future_base::_State_baseV2*, std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*>(std::once_flag&, void (std::__future_base::_State_baseV2::--Type <RET> for more, q to quit, c to continue without paging--c
*&&)(std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*), std::__future_base::_State_baseV2*&&, std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*&&, bool*&&) (__once=..., __f=@0x7fc849648570: (void (std::__future_base::_State_baseV2::*)(std::__future_base::_State_baseV2 * const, std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter>()> *, bool *)) 0x563c231f4a78 <std::__future_base::_State_baseV2::_M_do_set(std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>*, bool*)>) at /usr/include/c++/9/mutex:683
#21 0x0000563c231f4835 in std::__future_base::_State_baseV2::_M_set_result(std::function<std::unique_ptr<std::__future_base::_Result_base, std::__future_base::_Result_base::_Deleter> ()>, bool) (this=0x563c23c088b0, __res=..., __ignore_failure=false) at /usr/include/c++/9/future:401
#22 0x0000563c231f21ee in std::__future_base::_Async_state_impl<std::thread::_Invoker<std::tuple<spin_executor_async(std::shared_ptr<rclcpp::Node>, rclcpp::Executor&)::<lambda()> > >, void>::<lambda()>::operator()(void) const (this=0x563c23c088b0) at /usr/include/c++/9/future:1662
#23 0x0000563c231f397b in std::__invoke_impl<void, std::__future_base::_Async_state_impl<_BoundFn, _Res>::_Async_state_impl(_BoundFn&&) [with _BoundFn = std::thread::_Invoker<std::tuple<spin_executor_async(std::shared_ptr<rclcpp::Node>, rclcpp::Executor&)::<lambda()> > >; _Res = void]::<lambda()> >(std::__invoke_other, std::__future_base::_Async_state_impl<std::thread::_Invoker<std::tuple<spin_executor_async(std::shared_ptr<rclcpp::Node>, rclcpp::Executor&)::<lambda()> > >, void>::<lambda()> &&) (__f=...) at /usr/include/c++/9/bits/invoke.h:60
#24 0x0000563c231f391c in std::__invoke<std::__future_base::_Async_state_impl<_BoundFn, _Res>::_Async_state_impl(_BoundFn&&) [with _BoundFn = std::thread::_Invoker<std::tuple<spin_executor_async(std::shared_ptr<rclcpp::Node>, rclcpp::Executor&)::<lambda()> > >; _Res = void]::<lambda()> >(std::__future_base::_Async_state_impl<std::thread::_Invoker<std::tuple<spin_executor_async(std::shared_ptr<rclcpp::Node>, rclcpp::Executor&)::<lambda()> > >, void>::<lambda()> &&) (__fn=...) at /usr/include/c++/9/bits/invoke.h:95
#25 0x0000563c231f385e in std::thread::_Invoker<std::tuple<std::__future_base::_Async_state_impl<_BoundFn, _Res>::_Async_state_impl(_BoundFn&&) [with _BoundFn = std::thread::_Invoker<std::tuple<spin_executor_async(std::shared_ptr<rclcpp::Node>, rclcpp::Executor&)::<lambda()> > >; _Res = void]::<lambda()> > >::_M_invoke<0>(std::_Index_tuple<0>) (this=0x563c23c08da8) at /usr/include/c++/9/thread:244
#26 0x0000563c231f379f in std::thread::_Invoker<std::tuple<std::__future_base::_Async_state_impl<_BoundFn, _Res>::_Async_state_impl(_BoundFn&&) [with _BoundFn = std::thread::_Invoker<std::tuple<spin_executor_async(std::shared_ptr<rclcpp::Node>, rclcpp::Executor&)::<lambda()> > >; _Res = void]::<lambda()> > >::operator()(void) (this=0x563c23c08da8) at /usr/include/c++/9/thread:251
#27 0x0000563c231f32c6 in std::thread::_State_impl<std::thread::_Invoker<std::tuple<std::__future_base::_Async_state_impl<_BoundFn, _Res>::_Async_state_impl(_BoundFn&&) [with _BoundFn = std::thread::_Invoker<std::tuple<spin_executor_async(std::shared_ptr<rclcpp::Node>, rclcpp::Executor&)::<lambda()> > >; _Res = void]::<lambda()> > > >::_M_run(void) (this=0x563c23c08da0) at /usr/include/c++/9/thread:195
#28 0x00007fc84f772d84 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#29 0x00007fc84fbb3609 in start_thread (arg=<optimized out>) at pthread_create.c:477
#30 0x00007fc84f5af293 in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95

The callstack for thread 1:

#0  __lll_lock_wait (futex=futex@entry=0x563c23b17598, private=0) at lowlevellock.c:52
#1  0x00007fc84fbb60a3 in __GI___pthread_mutex_lock (mutex=0x563c23b17598) at ../nptl/pthread_mutex_lock.c:80
#2  0x00007fc84fcba3a1 in rclcpp::Executor::remove_callback_group_from_map(std::shared_ptr<rclcpp::CallbackGroup>, std::map<std::weak_ptr<rclcpp::CallbackGroup>, std::weak_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::owner_less<std::weak_ptr<rclcpp::CallbackGroup> >, std::allocator<std::pair<std::weak_ptr<rclcpp::CallbackGroup> const, std::weak_ptr<rclcpp::node_interfaces::NodeBaseInterface> > > >&, bool) ()
   from /opt/ros/rolling/lib/librclcpp.so
#3  0x00007fc84fcb8f4d in rclcpp::Executor::remove_node(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, bool) () from /opt/ros/rolling/lib/librclcpp.so
#4  0x00007fc84fcb42e4 in rclcpp::Executor::remove_node(std::shared_ptr<rclcpp::Node>, bool) () from /opt/ros/rolling/lib/librclcpp.so
#5  0x0000563c231eff4c in spin_executor_async (node=std::shared_ptr<class rclcpp::Node> (use count 3, weak count 1) = {...}, executor=...)
    at /root/control/src/ros2_control/controller_manager/test/test_controller_manager.cpp:151
#6  0x0000563c231f00ad in TestControllerManager_controller_parameters_Test::TestBody (this=0x563c23d26bd0) at /root/control/src/ros2_control/controller_manager/test/test_controller_manager.cpp:177
#7  0x0000563c23241c34 in testing::internal::HandleSehExceptionsInMethodIfSupported<testing::Test, void> (object=0x563c23d26bd0, method=&virtual testing::Test::TestBody(), 
    location=0x563c2326d73b "the test body") at /opt/ros/rolling/src/gtest_vendor/src/gtest.cc:2447
#8  0x0000563c2323a9f9 in testing::internal::HandleExceptionsInMethodIfSupported<testing::Test, void> (object=0x563c23d26bd0, method=&virtual testing::Test::TestBody(), location=0x563c2326d73b "the test body")
    at /opt/ros/rolling/src/gtest_vendor/src/gtest.cc:2483
#9  0x0000563c23216646 in testing::Test::Run (this=0x563c23d26bd0) at /opt/ros/rolling/src/gtest_vendor/src/gtest.cc:2522
#10 0x0000563c2321703f in testing::TestInfo::Run (this=0x563c238d4f30) at /opt/ros/rolling/src/gtest_vendor/src/gtest.cc:2703
#11 0x0000563c23217730 in testing::TestCase::Run (this=0x563c238d4db0) at /opt/ros/rolling/src/gtest_vendor/src/gtest.cc:2825
#12 0x0000563c23222e19 in testing::internal::UnitTestImpl::RunAllTests (this=0x563c238d4a40) at /opt/ros/rolling/src/gtest_vendor/src/gtest.cc:5216
#13 0x0000563c2324312e in testing::internal::HandleSehExceptionsInMethodIfSupported<testing::internal::UnitTestImpl, bool> (object=0x563c238d4a40, 
    method=(bool (testing::internal::UnitTestImpl::*)(class testing::internal::UnitTestImpl * const)) 0x563c23222b70 <testing::internal::UnitTestImpl::RunAllTests()>, 
    location=0x563c2326e140 "auxiliary test code (environments or event listeners)") at /opt/ros/rolling/src/gtest_vendor/src/gtest.cc:2447
#14 0x0000563c2323bb0d in testing::internal::HandleExceptionsInMethodIfSupported<testing::internal::UnitTestImpl, bool> (object=0x563c238d4a40, 
    method=(bool (testing::internal::UnitTestImpl::*)(class testing::internal::UnitTestImpl * const)) 0x563c23222b70 <testing::internal::UnitTestImpl::RunAllTests()>, 
    location=0x563c2326e140 "auxiliary test code (environments or event listeners)") at /opt/ros/rolling/src/gtest_vendor/src/gtest.cc:2483
#15 0x0000563c232217f8 in testing::UnitTest::Run (this=0x563c232b3520 <testing::UnitTest::GetInstance()::instance>) at /opt/ros/rolling/src/gtest_vendor/src/gtest.cc:4824
#16 0x0000563c2320e295 in RUN_ALL_TESTS () at /opt/ros/rolling/src/gtest_vendor/include/gtest/gtest.h:2370
#17 0x0000563c2320e217 in main (argc=1, argv=0x7fff2d24dfa8) at /opt/ros/rolling/src/gmock_vendor/src/gmock_main.cc:53

Metadata

Metadata

Assignees

Labels

bugSomething isn't working

Type

No type

Projects

No projects

Milestone

No milestone

Relationships

None yet

Development

No branches or pull requests

Issue actions