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

Segmentation fault with global Node #2666

Open
allbluelai opened this issue Nov 9, 2024 · 1 comment
Open

Segmentation fault with global Node #2666

allbluelai opened this issue Nov 9, 2024 · 1 comment
Assignees

Comments

@allbluelai
Copy link

allbluelai commented Nov 9, 2024

Bug report

Required Info:

  • Operating System:
    • Ubuntu 22.04 + VMware
  • Installation type:
    add backward_ros to source and
sudo apt-get -y install libdw-dev
// uncomment the macro
#define BACKWARD_HAS_DW 1

and build the source

  colcon build --merge-install --packages-skip-build-finished --cmake-args -DBUILD_TESTING=OFF -DCMAKE_BUILD_TYPE=Debug
  • Version or commit hash:
    • humble
  • DDS implementation:
    • rmw_fastrtps_cpp and rmw_cyclonedds_cpp
  • Client library (if applicable):
    • rclcpp

Steps to reproduce issue

// global.node
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

rclcpp::Node::SharedPtr g_node = nullptr;

int main(int argc, char *argv[]) {
  rclcpp::init(argc, argv);
  g_node = rclcpp::Node::make_shared("global_node");
  rclcpp::spin(g_node);
  rclcpp::shutdown();
  return 0;
}
// local_node.cpp
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

int main(int argc, char *argv[]) {
  rclcpp::init(argc, argv);
  rclcpp::Node::SharedPtr l_node = rclcpp::Node::make_shared("local_node");
  rclcpp::spin(l_node);
  rclcpp::shutdown();
  return 0;
}

Expected behavior

Exit without Segmentation fault when Ctrl+C

^C[INFO] [1731149893.815000507] [rclcpp]: signal_handler(signum=2)

Actual behavior

  • rmw_cyclonedds_cpp+global_node
  • rmw_cyclonedds_cpp+local_node
  • rmw_fastrtps_cpp+local_node
    All three above work fine:
$ RMW_IMPLEMENTATION=rmw_cyclonedds_cpp ros2 run cpp_pubsub global_node 
^C[INFO] [1731149893.815000507] [rclcpp]: signal_handler(signum=2)
$ RMW_IMPLEMENTATION=rmw_cyclonedds_cpp ros2 run cpp_pubsub local_node 
^C[INFO] [1731150107.206215360] [rclcpp]: signal_handler(signum=2)
$ RMW_IMPLEMENTATION=rmw_fastrtps_cpp ros2 run cpp_pubsub local_node 
^C[INFO] [1731150048.358643971] [rclcpp]: signal_handler(signum=2)

Only rmw_fastrtps_cpp+global_node throws Segmentation fault:

$ RMW_IMPLEMENTATION=rmw_fastrtps_cpp ros2 run cpp_pubsub global_node 
^C[INFO] [1731150009.632873683] [rclcpp]: signal_handler(signum=2)
cannot publish data, at /home/john/ros2_humble/src/ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/rmw_publish.cpp:62 during '__function__'
[ERROR] [1731150009.783284454] [global_node.rclcpp]: Error in destruction of rcl subscription handle: Failed to delete datareader, at /home/john/ros2_humble/src/ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/subscription.cpp:52, at /home/john/ros2_humble/src/ros2/rcl/rcl/src/rcl/subscription.c:184
cannot publish data, at /home/john/ros2_humble/src/ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/rmw_publish.cpp:62 during '__function__'
Fail in delete datareader, at /home/john/ros2_humble/src/ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/rmw_service.cpp:104 during '__function__'
Stack trace (most recent call last):
#31   Source "/usr/include/c++/11/bits/shared_ptr_base.h", line 348, in _M_dispose [0x72ccb903e909]
        346:       virtual void
        347:       _M_dispose() noexcept
      > 348:       { delete _M_ptr; }
        349: 
        350:       virtual void
        351:       _M_destroy() noexcept
#30   Source "/home/john/ros2_humble/src/ros2/rclcpp/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp", line 119, in ~NodeParameters [0x72ccb9054d27]
        116: }
        117: 
        118: NodeParameters::~NodeParameters()
      > 119: {}
        120: 
        121: RCLCPP_LOCAL
        122: bool
#29   Source "/home/john/ros2_humble/src/ros2/rclcpp/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp", line 119, in ~NodeParameters [0x72ccb9054ca7]
        116: }
        117: 
        118: NodeParameters::~NodeParameters()
      > 119: {}
        120: 
        121: RCLCPP_LOCAL
        122: bool
#28   Source "/usr/include/c++/11/bits/shared_ptr.h", line 122, in ~shared_ptr [0x72ccb905c33f]
        119:    * pointer see `std::shared_ptr::owner_before` and `std::owner_less`.
        120:   */
        121:   template<typename _Tp>
      > 122:     class shared_ptr : public __shared_ptr<_Tp>
        123:     {
        124:       template<typename... _Args>
        125: 	using _Constructible = typename enable_if<
#27   Source "/usr/include/c++/11/bits/shared_ptr_base.h", line 1154, in ~__shared_ptr [0x72ccb905c31f]
       1152:       __shared_ptr(const __shared_ptr&) noexcept = default;
       1153:       __shared_ptr& operator=(const __shared_ptr&) noexcept = default;
      >1154:       ~__shared_ptr() = default;
       1155: 
       1156:       template<typename _Yp, typename = _Compatible<_Yp>>
       1157: 	__shared_ptr(const __shared_ptr<_Yp, _Lp>& __r) noexcept
#26   Source "/usr/include/c++/11/bits/shared_ptr_base.h", line 705, in ~__shared_count [0x6421c587cf48]
        702:       ~__shared_count() noexcept
        703:       {
        704: 	if (_M_pi != nullptr)
      > 705: 	  _M_pi->_M_release();
        706:       }
        707: 
        708:       __shared_count(const __shared_count& __r) noexcept
#25   Source "/usr/include/c++/11/bits/shared_ptr_base.h", line 168, in _M_release [0x6421c587d668]
        165: 	if (__gnu_cxx::__exchange_and_add_dispatch(&_M_use_count, -1) == 1)
        166: 	  {
        167:             _GLIBCXX_SYNCHRONIZATION_HAPPENS_AFTER(&_M_use_count);
      > 168: 	    _M_dispose();
        169: 	    // There must be a memory barrier between dispose() and destroy()
        170: 	    // to ensure that the effects of dispose() are observed in the
        171: 	    // thread that runs destroy().
#24   Source "/usr/include/c++/11/bits/shared_ptr_base.h", line 528, in _M_dispose [0x72ccb9083f00]
        525:       virtual void
        526:       _M_dispose() noexcept
        527:       {
      > 528: 	allocator_traits<_Alloc>::destroy(_M_impl._M_alloc(), _M_ptr());
        529:       }
        530: 
        531:       // Override because the allocator needs to know the dynamic type
#23   Source "/usr/include/c++/11/bits/alloc_traits.h", line 535, in destroy<rclcpp::ParameterService> [0x72ccb9084bfe]
        532: 	noexcept(is_nothrow_destructible<_Up>::value)
        533: 	{
        534: #if __cplusplus <= 201703L
      > 535: 	  __a.destroy(__p);
        536: #else
        537: 	  std::destroy_at(__p);
        538: #endif
#22   Source "/usr/include/c++/11/ext/new_allocator.h", line 168, in destroy<rclcpp::ParameterService> [0x72ccb90855b3]
        165: 	void
        166: 	destroy(_Up* __p)
        167: 	noexcept(std::is_nothrow_destructible<_Up>::value)
      > 168: 	{ __p->~_Up(); }
        169: #else
        170:       // _GLIBCXX_RESOLVE_LIB_DEFECTS
        171:       // 402. wrong new expression in [some_] allocator::construct
#21   Source "/home/john/ros2_humble/src/ros2/rclcpp/rclcpp/include/rclcpp/parameter_service.hpp", line 37, in ~ParameterService [0x72ccb9085543]
         34: namespace rclcpp
         35: {
         36: 
      >  37: class ParameterService
         38: {
         39: public:
         40:   RCLCPP_SMART_PTR_DEFINITIONS(ParameterService)
#20   Source "/usr/include/c++/11/bits/shared_ptr.h", line 122, in ~shared_ptr [0x72ccb908551f]
        119:    * pointer see `std::shared_ptr::owner_before` and `std::owner_less`.
        120:   */
        121:   template<typename _Tp>
      > 122:     class shared_ptr : public __shared_ptr<_Tp>
        123:     {
        124:       template<typename... _Args>
        125: 	using _Constructible = typename enable_if<
#19   Source "/usr/include/c++/11/bits/shared_ptr_base.h", line 1154, in ~__shared_ptr [0x72ccb90854ff]
       1152:       __shared_ptr(const __shared_ptr&) noexcept = default;
       1153:       __shared_ptr& operator=(const __shared_ptr&) noexcept = default;
      >1154:       ~__shared_ptr() = default;
       1155: 
       1156:       template<typename _Yp, typename = _Compatible<_Yp>>
       1157: 	__shared_ptr(const __shared_ptr<_Yp, _Lp>& __r) noexcept
#18   Source "/usr/include/c++/11/bits/shared_ptr_base.h", line 705, in ~__shared_count [0x6421c587cf48]
        702:       ~__shared_count() noexcept
        703:       {
        704: 	if (_M_pi != nullptr)
      > 705: 	  _M_pi->_M_release();
        706:       }
        707: 
        708:       __shared_count(const __shared_count& __r) noexcept
#17   Source "/usr/include/c++/11/bits/shared_ptr_base.h", line 168, in _M_release [0x6421c587d668]
        165: 	if (__gnu_cxx::__exchange_and_add_dispatch(&_M_use_count, -1) == 1)
        166: 	  {
        167:             _GLIBCXX_SYNCHRONIZATION_HAPPENS_AFTER(&_M_use_count);
      > 168: 	    _M_dispose();
        169: 	    // There must be a memory barrier between dispose() and destroy()
        170: 	    // to ensure that the effects of dispose() are observed in the
        171: 	    // thread that runs destroy().
#16   Source "/usr/include/c++/11/bits/shared_ptr_base.h", line 528, in _M_dispose [0x72ccb9149984]
        525:       virtual void
        526:       _M_dispose() noexcept
        527:       {
      > 528: 	allocator_traits<_Alloc>::destroy(_M_impl._M_alloc(), _M_ptr());
        529:       }
        530: 
        531:       // Override because the allocator needs to know the dynamic type
#15   Source "/usr/include/c++/11/bits/alloc_traits.h", line 535, in destroy<rclcpp::Service<rcl_interfaces::srv::ListParameters> > [0x72ccb914b4f4]
        532: 	noexcept(is_nothrow_destructible<_Up>::value)
        533: 	{
        534: #if __cplusplus <= 201703L
      > 535: 	  __a.destroy(__p);
        536: #else
        537: 	  std::destroy_at(__p);
        538: #endif
#14   Source "/usr/include/c++/11/ext/new_allocator.h", line 168, in destroy<rclcpp::Service<rcl_interfaces::srv::ListParameters> > [0x72ccb914f8aa]
        165: 	void
        166: 	destroy(_Up* __p)
        167: 	noexcept(std::is_nothrow_destructible<_Up>::value)
      > 168: 	{ __p->~_Up(); }
        169: #else
        170:       // _GLIBCXX_RESOLVE_LIB_DEFECTS
        171:       // 402. wrong new expression in [some_] allocator::construct
#13   Source "/home/john/ros2_humble/src/ros2/rclcpp/rclcpp/include/rclcpp/service.hpp", line 435, in ~Service [0x72ccb914a331]
        433:   virtual ~Service()
        434:   {
      > 435:   }
        436: 
        437:   /// Take the next request from the service.
        438:   /**
#12   Source "/home/john/ros2_humble/src/ros2/rclcpp/rclcpp/src/rclcpp/service.cpp", line 38, in ~ServiceBase [0x72ccb9162821]
         35: ServiceBase::~ServiceBase()
         36: {
         37:   clear_on_new_request_callback();
      >  38: }
         39: 
         40: bool
         41: ServiceBase::take_type_erased_request(void * request_out, rmw_request_id_t & request_id_out)
#11   Source "/usr/include/c++/11/bits/shared_ptr.h", line 122, in ~shared_ptr [0x72ccb9022775]
        119:    * pointer see `std::shared_ptr::owner_before` and `std::owner_less`.
        120:   */
        121:   template<typename _Tp>
      > 122:     class shared_ptr : public __shared_ptr<_Tp>
        123:     {
        124:       template<typename... _Args>
        125: 	using _Constructible = typename enable_if<
#10   Source "/usr/include/c++/11/bits/shared_ptr_base.h", line 1154, in ~__shared_ptr [0x72ccb9022755]
       1152:       __shared_ptr(const __shared_ptr&) noexcept = default;
       1153:       __shared_ptr& operator=(const __shared_ptr&) noexcept = default;
      >1154:       ~__shared_ptr() = default;
       1155: 
       1156:       template<typename _Yp, typename = _Compatible<_Yp>>
       1157: 	__shared_ptr(const __shared_ptr<_Yp, _Lp>& __r) noexcept
#9    Source "/usr/include/c++/11/bits/shared_ptr_base.h", line 705, in ~__shared_count [0x6421c587cf48]
        702:       ~__shared_count() noexcept
        703:       {
        704: 	if (_M_pi != nullptr)
      > 705: 	  _M_pi->_M_release();
        706:       }
        707: 
        708:       __shared_count(const __shared_count& __r) noexcept
#8    Source "/usr/include/c++/11/bits/shared_ptr_base.h", line 168, in _M_release [0x6421c587d668]
        165: 	if (__gnu_cxx::__exchange_and_add_dispatch(&_M_use_count, -1) == 1)
        166: 	  {
        167:             _GLIBCXX_SYNCHRONIZATION_HAPPENS_AFTER(&_M_use_count);
      > 168: 	    _M_dispose();
        169: 	    // There must be a memory barrier between dispose() and destroy()
        170: 	    // to ensure that the effects of dispose() are observed in the
        171: 	    // thread that runs destroy().
#7    Source "/usr/include/c++/11/bits/shared_ptr_base.h", line 442, in _M_dispose [0x72ccb914902b]
        440:       virtual void
        441:       _M_dispose() noexcept
      > 442:       { _M_impl._M_del()(_M_impl._M_ptr); }
        443: 
        444:       virtual void
        445:       _M_destroy() noexcept
#6    Source "/home/john/ros2_humble/src/ros2/rclcpp/rclcpp/include/rclcpp/service.hpp", line 319, in operator() [0x72ccb91334de]
        316:     service_handle_ = std::shared_ptr<rcl_service_t>(
        317:       new rcl_service_t, [handle = node_handle_, service_name](rcl_service_t * service)
        318:       {
      > 319:         if (rcl_service_fini(service, handle.get()) != RCL_RET_OK) {
        320:           RCLCPP_ERROR(
        321:             rclcpp::get_node_logger(handle.get()).get_child("rclcpp"),
        322:             "Error in destruction of rcl service handle: %s",
#5    Source "/home/john/ros2_humble/src/ros2/rcl/rcl/src/rcl/service.c", line 196, in rcl_service_fini [0x72ccb8534950]
        193:     if (!rmw_node) {
        194:       return RCL_RET_INVALID_ARGUMENT;
        195:     }
      > 196:     rmw_ret_t ret = rmw_destroy_service(rmw_node, service->impl->rmw_handle);
        197:     if (ret != RMW_RET_OK) {
        198:       RCL_SET_ERROR_MSG(rmw_get_error_string().str);
        199:       result = RCL_RET_ERROR;
#4    Source "/home/john/ros2_humble/src/ros2/rmw_implementation/rmw_implementation/src/functions.cpp", line 523, in rmw_destroy_service [0x72ccb84dea1e]
        520:     const rmw_node_t *, const rosidl_service_type_support_t *, const char *,
        521:     const rmw_qos_profile_t *))
        522: 
      > 523: RMW_INTERFACE_FN(
        524:   rmw_destroy_service,
        525:   rmw_ret_t, RMW_RET_ERROR,
        526:   2, ARG_TYPES(rmw_node_t *, rmw_service_t *))
#3    Source "/home/john/ros2_humble/src/ros2/rmw_fastrtps/rmw_fastrtps_cpp/src/rmw_service.cpp", line 501, in rmw_destroy_service [0x72ccb6c70363]
        498:     eprosima_fastrtps_identifier,
        499:     return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
        500: 
      > 501:   return rmw_fastrtps_shared_cpp::__rmw_destroy_service(
        502:     eprosima_fastrtps_identifier, node, service);
        503: }
#2    Source "/home/john/ros2_humble/src/ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/rmw_service.cpp", line 131, in __rmw_destroy_service [0x72ccb6ba567d]
        128:     }
        129: 
        130:     // Delete topics and unregister types
      > 131:     remove_topic_and_type(participant_info, request_topic, info->request_type_support_);
        132:     remove_topic_and_type(participant_info, response_topic, info->response_type_support_);
        133: 
        134:     // Delete CustomServiceInfo structure
#1    Source "/home/john/ros2_humble/src/ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/utils.cpp", line 124, in remove_topic_and_type [0x72ccb6bc8e8e]
        121:   // TODO(MiguelCompany): We only create Topic instances at the moment, but this may
        122:   // change in the future if we start supporting other kinds of TopicDescription
        123:   // (like ContentFilteredTopic)
      > 124:   auto topic = dynamic_cast<const eprosima::fastdds::dds::Topic *>(topic_desc);
        125: 
        126:   if (nullptr != topic) {
        127:     participant_info->participant_->delete_topic(topic);
#0    Object "/usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.30", at 0x72ccb82acc9d, in __dynamic_cast
Segmentation fault (Signal sent by the kernel [(nil)])
[ros2run]: Segmentation fault

Additional information

The not_composable.cpp also throws Segmentation fault.

@MichaelOrlov
Copy link
Contributor

@allbluelai The root cause of the segfault is likely that the domain participant was already destructed when we reached the destructor of the globally defined node.
The problem is that order of destruction for the globally defined objects is in the "grey" area of the C++ and not defined.
A possible workaround would be to try to call the destructor of the globally defined node explicitly somewhere in the main function.

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

No branches or pull requests

3 participants