Skip to content

terminate called after throwing an instance of 'std::system_error' what(): Resource deadlock avoided #1519

@LouisChen1905

Description

@LouisChen1905

Bug report

Required Info:

  • Operating System:
    • ubuntu 20.04-->
  • Installation type:
    • from source
  • Version or commit hash:
    • eloquent
  • DDS implementation:
    • Fast-RTPS
  • Client library (if applicable):
    • rclcpp

Steps to reproduce issue

I'm writing gtest scripts. My SetUp():

void SetUp()
{
        auto context = contexts::default_context::get_global_default_context();
        auto options = NodeOptions()
                .context(context)
            // BUG: if set true, test would crash: std::system_error Resource deadlock avoided!
                .use_intra_process_comms(true)
                .automatically_declare_parameters_from_overrides(true);
        mappingNode_ = std::make_shared<Node>("mapping", options);
        bool res = false;
        res = Mapping::getInstance()->initialize(mappingNode_);
        if(!res){
            RCLCPP_ERROR(mappingNode_->get_logger(), "Failed to initialize.");
        }

        executor = std::make_shared<executors::MultiThreadedExecutor>
                   (executor::ExecutorArgs(), 2);
        executor->add_node(mappingNode_);
}

In TEST_F(), if I used executor.spin_until_future_complete() to wait some messages, test program would crash when entering the second TEST_F(). If I use spin_some() instead, the program would run without crashing.
You can find the line above use_intra_process_comms(true). If it's set to true, 'Resource deadlock avoided' would occur in the second test case.

TEST_F()
{
    promise<void> promise;
    Subscription<Mode>::SharedPtr ModeSub;
    auto ModeCB = [&ModeSub, &promise](Mode::SharedPtr msg)->void{
      if(msg->mode == Mode::W &&
         msg->state == Mode::I){
        promise.set_value();
        ModeSub.reset();
      }
    };
    ModeSub =
        pubNode_->create_subscription<Mode>("aa",
                                                   QoS(QoSInitialization::from_rmw(rmw_qos_profile_default)),
                                                   ModeCB);
    shared_future<void> future(promise.get_future());
    ASSERT_EQ(executor->spin_until_future_complete(future, 2s), executor::FutureReturnCode::SUCCESS);
}
0  __GI_raise (sig=sig@entry=6) at ../sysdeps/unix/sysv/linux/raise.c:50
#1  0x00007ffff6737859 in __GI_abort () at abort.c:79
#2  0x00007ffff6b0c951 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#3  0x00007ffff6b1847c in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#4  0x00007ffff6b17459 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#5  0x00007ffff6b17e11 in __gxx_personality_v0 () from /lib/x86_64-linux-gnu/libstdc++.so.6
#6  0x00007ffff6914bdf in ?? () from /lib/x86_64-linux-gnu/libgcc_s.so.1
#7  0x00007ffff6915271 in _Unwind_RaiseException () from /lib/x86_64-linux-gnu/libgcc_s.so.1
#8  0x00007ffff6b1878c in __cxa_throw () from /lib/x86_64-linux-gnu/libstdc++.so.6
#9  0x00007ffff6b0f77f in std::__throw_system_error(int) () from /lib/x86_64-linux-gnu/libstdc++.so.6
#10 0x00007ffff7af3a99 in std::__shared_mutex_pthread::lock (this=0x55555617af50) at /usr/include/c++/9/shared_mutex:188
#11 0x00007ffff7af3b34 in std::shared_timed_mutex::lock (this=0x55555617af50) at /usr/include/c++/9/shared_mutex:459
#12 0x00007ffff7af519b in std::unique_lock<std::shared_timed_mutex>::lock (this=0x7ffffffea490)
    at /usr/include/c++/9/bits/unique_lock.h:141
#13 0x00007ffff7af45dd in std::unique_lock<std::shared_timed_mutex>::unique_lock (this=0x7ffffffea490, __m=...)
    at /usr/include/c++/9/bits/unique_lock.h:71
#14 0x00007ffff7af2d3e in rclcpp::experimental::IntraProcessManager::remove_subscription (this=0x55555617aea0, 
    intra_process_subscription_id=2)
    at /home/chervon/ros2_eloquent_source/src/ros2/rclcpp/rclcpp/src/rclcpp/intra_process_manager.cpp:86
#15 0x00007ffff7bd3b67 in rclcpp::SubscriptionBase::~SubscriptionBase (this=0x55555619ac90, __in_chrg=<optimized out>)
    at /home/chervon/ros2_eloquent_source/src/ros2/rclcpp/rclcpp/src/rclcpp/subscription_base.cpp:96
--Type <RET> for more, q to quit, c to continue without paging--
pp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >::~Subscription (this=0x55555619ac90, __in_chrg=<optimized out>)
    at /home/chervon/ros2_eloquent_source/src/ros2/rclcpp/rclcpp/include/rclcpp/subscription.hpp:67
#17 0x00007ffff7c02087 in __gnu_cxx::new_allocator<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > >::destroy<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > > (this=0x55555619ac90, __p=0x55555619ac90)
    at /usr/include/c++/9/ext/new_allocator.h:153
#18 0x00007ffff7c00065 in std::allocator_traits<std::allocator<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > > >::destroy<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > > (__a=..., __p=0x55555619ac90)
    at /usr/include/c++/9/bits/alloc_traits.h:497

#19 0x00007ffff7bfd13d in std::_Sp_counted_ptr_inplace<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, std::allocator<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > >, (__gnu_cxx::_Lock_policy)2>::_M_dispose (this=0x55555619ac80)
    at /usr/include/c++/9/bits/shared_ptr_base.h:557
#20 0x000055555563c380 in std::_Sp_counted_base<(__gnu_cxx::_Lock_policy)2>::_M_release (this=0x55555619ac80) at /usr/include/c++/9/bits/shared_ptr_base.h:155
#21 0x0000555555637ec3 in std::__shared_count<(__gnu_cxx::_Lock_policy)2>::~__shared_count (this=0x7ffffffeb7d8, __in_chrg=<optimized out>) at /usr/include/c++/9/bits/shared_ptr_base.h:730
#22 0x00007ffff7bd9ad8 in std::__shared_ptr<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, (__gnu_cxx::_Lock_policy)2>::~__shared_ptr (this=0x7ffffffeb7d0, __in_chrg=<optimized out>)
    at /usr/include/c++/9/bits/shared_ptr_base.h:1169
#23 0x00007ffff7bda7aa in std::__shared_ptr<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, (__gnu_cxx::_Lock_policy)2>::reset (this=0x5555561a2b80) at /usr/include/c++/9/bits/shared_ptr_base.h:1287
#24 0x00007ffff7bd785e in rclcpp::TimeSource::detachNode (this=0x5555561a2ac8) at /home/chervon/ros2_eloquent_source/src/ros2/rclcpp/rclcpp/src/rclcpp/time_source.cpp:132
#25 0x00007ffff7bd7ed0 in rclcpp::TimeSource::~TimeSource (this=0x5555561a2ac8, __in_chrg=<optimized out>) at /home/chervon/ros2_eloquent_source/src/ros2/rclcpp/rclcpp/src/rclcpp/time_source.cpp:180
#26 0x00007ffff7b5ec0e in rclcpp::node_interfaces::NodeTimeSource::~NodeTimeSource (this=0x5555561a2a50, __in_chrg=<optimized out>)
    at /home/chervon/ros2_eloquent_source/src/ros2/rclcpp/rclcpp/src/rclcpp/node_interfaces/node_time_source.cpp:49
#27 0x00007ffff7b5ecaa in rclcpp::node_interfaces::NodeTimeSource::~NodeTimeSource (this=0x5555561a2a50, __in_chrg=<optimized out>)
    at /home/chervon/ros2_eloquent_source/src/ros2/rclcpp/rclcpp/src/rclcpp/node_interfaces/node_time_source.cpp:50
#28 0x00007ffff7b1b780 in std::_Sp_counted_ptr<rclcpp::node_interfaces::NodeTimeSource*, (__gnu_cxx::_Lock_policy)2>::_M_dispose (this=0x555556198760) at /usr/include/c++/9/bits/shared_ptr_base.h:377
#29 0x000055555563c380 in std::_Sp_counted_base<(__gnu_cxx::_Lock_policy)2>::_M_release (this=0x555556198760) at /usr/include/c++/9/bits/shared_ptr_base.h:155
#30 0x0000555555637ec3 in std::__shared_count<(__gnu_cxx::_Lock_policy)2>::~__shared_count (this=0x555555fbb9c0, __in_chrg=<optimized out>) at /usr/include/c++/9/bits/shared_ptr_base.h:730
#31 0x00007ffff7b1416c in std::__shared_ptr<rclcpp::node_interfaces::NodeTimeSourceInterface, (__gnu_cxx::_Lock_policy)2>::~__shared_ptr (this=0x555555fbb9b8, __in_chrg=<optimized out>)
    at /usr/include/c++/9/bits/shared_ptr_base.h:1169
#32 0x00007ffff7b1418c in std::shared_ptr<rclcpp::node_interfaces::NodeTimeSourceInterface>::~shared_ptr (this=0x555555fbb9b8, __in_chrg=<optimized out>) at /usr/include/c++/9/bits/shared_ptr.h:103
#33 0x00007ffff7b11fb0 in rclcpp::Node::~Node (this=0x555555fbb920, __in_chrg=<optimized out>) at /home/chervon/ros2_eloquent_source/src/ros2/rclcpp/rclcpp/src/rclcpp/node.cpp:185
#34 0x000055555568cec5 in __gnu_cxx::new_allocator<rclcpp::Node>::destroy<rclcpp::Node> (this=0x555555fbb920, __p=0x555555fbb920) at /usr/include/c++/9/ext/new_allocator.h:153
#35 0x000055555568b483 in std::allocator_traits<std::allocator<rclcpp::Node> >::destroy<rclcpp::Node> (__a=..., __p=0x555555fbb920) at /usr/include/c++/9/bits/alloc_traits.h:497
#36 0x0000555555687d19 in std::_Sp_counted_ptr_inplace<rclcpp::Node, std::allocator<rclcpp::Node>, (__gnu_cxx::_Lock_policy)2>::_M_dispose (this=0x555555fbb910) at /usr/include/c++/9/bits/shared_ptr_base.h:557
#37 0x000055555563c380 in std::_Sp_counted_base<(__gnu_cxx::_Lock_policy)2>::_M_release (this=0x555555fbb910) at /usr/include/c++/9/bits/shared_ptr_base.h:155
#38 0x0000555555637ec3 in std::__shared_count<(__gnu_cxx::_Lock_policy)2>::~__shared_count (this=0x555555fbef50, __in_chrg=<optimized out>) at /usr/include/c++/9/bits/shared_ptr_base.h:730
#39 0x00005555556351de in std::__shared_ptr<rclcpp::Node, (__gnu_cxx::_Lock_policy)2>::~__shared_ptr (this=0x555555fbef48, __in_chrg=<optimized out>) at /usr/include/c++/9/bits/shared_ptr_base.h:1169
#40 0x00005555556351fe in std::shared_ptr<rclcpp::Node>::~shared_ptr (this=0x555555fbef48, __in_chrg=<optimized out>) at /usr/include/c++/9/bits/shared_ptr.h:103

Expected behavior

Run through each test case.

Actual behavior

The first test case passed OK. But test program crashed when entering the second test case.

Metadata

Metadata

Assignees

No one assigned

    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