ros / ros_comm

ROS communications-related packages, including core client libraries (roscpp, rospy, roslisp) and graph introspection tools (rostopic, rosnode, rosservice, rosparam).
http://wiki.ros.org/ros_comm
761 stars 912 forks source link

[node_handle] run simple code will crash, terminate called after throwing an instance of 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >' #2215

Open Sunriseyms opened 2 years ago

Sunriseyms commented 2 years ago
int main(int argc, char* argv[]) {
  ros::init(ros::VP_string(), "test");
  static std::shared_ptr<ros::NodeHandle> n;
  n = std::make_shared<ros::NodeHandle>();
  return 0;
}

when I run above code will crash, this crash message is:

terminate called after throwing an instance of 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector >' what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument Aborted (core dumped)

coredump backstrace is:

(gdb) bt

0 __GI_raise (sig=sig@entry=6) at ../sysdeps/unix/sysv/linux/raise.c:51

1 0x00007ffff66aa921 in __GI_abort () at abort.c:79

2 0x00007ffff6cff957 in ?? () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6

3 0x00007ffff6d05ae6 in ?? () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6

4 0x00007ffff6d04b49 in ?? () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6

5 0x00007ffff6d054b8 in __gxx_personality_v0 () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6

6 0x00007ffff6a6b573 in ?? () from /lib/x86_64-linux-gnu/libgcc_s.so.1

7 0x00007ffff6a6bdf5 in _Unwind_Resume () from /lib/x86_64-linux-gnu/libgcc_s.so.1

8 0x00007ffff75280d2 in ros::NodeHandle::destruct (this=0x555555789020) at /home/yangms/sec/ws/ros_source/src/ros_comm/roscpp/src/libros/node_handle.cpp:188

9 0x00007ffff752798c in ros::NodeHandle::~NodeHandle (this=0x555555789020, __in_chrg=) at /home/yangms/sec/ws/ros_source/src/ros_comm/roscpp/src/libros/node_handle.cpp:133

10 0x000055555555cca1 in std::_Sp_counted_base<(__gnu_cxx::_Lock_policy)2>::_M_release (this=0x555555789010) at /usr/include/c++/7/bits/shared_ptr_base.h:154

11 std::shared_count<(__gnu_cxx::_Lock_policy)2>::~shared_count (this=, __in_chrg=) at /usr/include/c++/7/bits/shared_ptr_base.h:684

12 std::shared_ptr<ros::NodeHandle, (__gnu_cxx::_Lock_policy)2>::~shared_ptr (this=, __in_chrg=) at /usr/include/c++/7/bits/shared_ptr_base.h:1123

13 std::shared_ptr::~shared_ptr (this=, __in_chrg=) at /usr/include/c++/7/bits/shared_ptr.h:93

14 0x00007ffff66ad161 in run_exit_handlers (status=0, listp=0x7ffff6a55718 <exit_funcs>, run_list_atexit=run_list_atexit@entry=true, run_dtors=run_dtors@entry=true) at exit.c:108

15 0x00007ffff66ad25a in __GI_exit (status=) at exit.c:139

16 0x00007ffff668bbfe in __libc_start_main (main=0x55555555ae30 <main(int, char**)>, argc=1, argv=0x7fffffffd9c8, init=, fini=, rtld_fini=,

stack_end=0x7fffffffd9b8) at ../csu/libc-start.c:344

17 0x000055555555c13a in _start ()

Sunriseyms commented 2 years ago

Reason: where throw exception_detail? call TopicManager::instance()->shutdown()after TopicManager is destroy;the call chain is NodeHandler::~NodeHandler()->NodeHandler::destruct()->ros::shutdown()->TopicManager::instance()->shutdown();

when NodeHandle is destroy, it will call NodeHandle destruct(), collection is raw pointer to keep the reference to TopicManager::instance(), this code is first `delete collection, then it will callros::shutdown()after, when collection_ is the last reference toTopicManager::instance()`, it will crash.

void NodeHandle::destruct()
{
  delete collection_;

  boost::mutex::scoped_lock lock(g_nh_refcount_mutex);

  --g_nh_refcount;

  if (g_nh_refcount == 0 && g_node_started_by_nh)
  {
    ros::shutdown();
  }
}

Resolution:

  1. removedelete collection_ after ros::shutdown(); I test this code, it is fine; like this:

    void NodeHandle::destruct()
    {
    boost::mutex::scoped_lock lock(g_nh_refcount_mutex);
    
    --g_nh_refcount;
    
    if (g_nh_refcount == 0 && g_node_started_by_nh)
    {
    ros::shutdown();
    }
    delete collection_;
    }
  2. change raw pointer to smart pointer for collection_
    // NodeHandleBackingCollection* collection_;
    boost::shared_ptr<NodeHandleBackingCollection> collection_;

other way, if you can ensure the NodeHandle destroy before TopicManage() destroy, it also fine, like below code:

int main(int argc, char* argv[]) {
  ros::init(ros::VP_string(), "test");
  std::shared_ptr<ros::NodeHandle> n;
  n = std::make_shared<ros::NodeHandle>();
  return 0;
}
int main(int argc, char* argv[]) {
  ros::init(ros::VP_string(), "test");
  static std::shared_ptr<ros::NodeHandle> n = std::make_shared<ros::NodeHandle>();
  return 0;
}