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

Deadlock when using MultiThreadedExecutor #650

Closed
hplatou opened this issue Dec 12, 2022 · 14 comments
Closed

Deadlock when using MultiThreadedExecutor #650

hplatou opened this issue Dec 12, 2022 · 14 comments

Comments

@hplatou
Copy link

hplatou commented Dec 12, 2022

Bug report

Required Info:

  • Operating System:
    • Ubuntu 22.04, Humble
  • Installation type:
    • binaries
  • Version or commit hash:
    • v6.2.2
  • DDS implementation:
    • Fast-RTPS
  • Client library (if applicable):
    • rclcpp

Steps to reproduce issue

Running this simple example with a MultiThreadedExecutor eventually causes a deadlock (typically within a few seconds). From the debugger it seems to be stuck on WaitSetImpl::wait (see attached stack trace). This behavior seems to be introduced by #633

class Sender : public rclcpp::Node
{
  public:
    Sender()
    : Node("sender"), count_(0)
    {
      publisher_ = this->create_publisher<std_msgs::msg::UInt32>("tick", 100);
      timer_ = this->create_wall_timer(
        10ms, std::bind(&Sender::callback, this));
    }

  private:
    void callback()
    { 
      auto message = std_msgs::msg::UInt32();
      message.data = count_ ++;
      std::cout << "Sending tick: " << message.data << "..." << std::endl;
      publisher_->publish(message);
    }

    rclcpp::TimerBase::SharedPtr timer_;
    rclcpp::Publisher<std_msgs::msg::UInt32>::SharedPtr publisher_;
    size_t count_;
};



int main(int argc, char ** argv)
{
  rclcpp::init(argc, argv);

  auto node = std::make_shared<Sender>();
  rclcpp::executors::MultiThreadedExecutor executor;
  std::cout << "Created multithreaded executor. Num threads: " << executor.get_number_of_threads() << std::endl;
  executor.add_node(node);
  executor.spin();
  
  rclcpp::shutdown();
  return 0;
}

Stacktrace when stuck:

libc.so.6!__futex_abstimed_wait_common64(int private, _Bool cancel, const struct timespec * abstime, int op, unsigned int expected, unsigned int * futex_word) (futex-internal.c:57)
libc.so.6!__futex_abstimed_wait_common(_Bool cancel, int private, const struct timespec * abstime, clockid_t clockid, unsigned int expected, unsigned int * futex_word) (futex-internal.c:87)
libc.so.6!__GI___futex_abstimed_wait_cancelable64(unsigned int * futex_word, unsigned int expected, clockid_t clockid, const struct timespec * abstime, int private) (futex-internal.c:139)
libc.so.6!__pthread_cond_wait_common(pthread_mutex_t * mutex, pthread_cond_t * cond) (pthread_cond_wait.c:503)
libc.so.6!___pthread_cond_wait(pthread_cond_t * cond, pthread_mutex_t * mutex) (pthread_cond_wait.c:627)
libfastrtps.so.2.6!eprosima::fastdds::dds::detail::WaitSetImpl::wait(std::vector<eprosima::fastdds::dds::Condition*, std::allocator<eprosima::fastdds::dds::Condition*> >&, eprosima::fastrtps::Time_t const&) (Unknown Source:0)
libfastrtps.so.2.6!eprosima::fastdds::dds::WaitSet::wait(std::vector<eprosima::fastdds::dds::Condition*, std::allocator<eprosima::fastdds::dds::Condition*> >&, eprosima::fastrtps::Time_t) const (Unknown Source:0)
librmw_fastrtps_shared_cpp.so!rmw_fastrtps_shared_cpp::__rmw_wait(char const*, rmw_subscriptions_s*, rmw_guard_conditions_s*, rmw_services_s*, rmw_clients_s*, rmw_events_s*, rmw_wait_set_s*, rmw_time_s const*) (Unknown Source:0)
librmw_fastrtps_shared_cpp.so![Unknown/Just-In-Time compiled code] (Unknown Source:0)
libc.so.6!start_thread(void * arg) (pthread_create.c:442)
libc.so.6!clone3() (clone3.S:81)

Expected behavior

No deadlock

Actual behavior

Callback stops executing, typically within a few seconds

@fujitatomoya
Copy link
Collaborator

@hplatou could be related to eProsima/Fast-DDS#2961 ? that is something we have experienced before.

I think eProsima/Fast-DDS#2976 is not released yet as humble patch.

@MiguelCompany
Copy link
Collaborator

eProsima/Fast-DDS#2976 has been released with Fast DDS v2.6.3, which is pending humble sync.

It seems a sync is planned for Dec 16th

@hplatou
Copy link
Author

hplatou commented Dec 19, 2022

Thanks for your answers, but sadly, the 2.6.3 update of Fast DDS did not fix the problem. Only way I can make it work is to build the 6.2.1 version of rmw_fastrtps from source.

@fujitatomoya
Copy link
Collaborator

@iuhilnehc-ynos @Barry-Xu-2018 CCed.

@iuhilnehc-ynos
Copy link
Contributor

I can reproduce this issue with the latest humble repos.

repo commit id
Fast-DDS eProsima/Fast-DDS@dfe8204
rmw_fastrtps 8955d4e

application log (replace with the issue code in examples/rclcpp/topics/minimal_publisher/member_function.cpp)

chenlh ros2-humble $ ros2 run examples_rclcpp_minimal_publisher publisher_member_function
Created multithreaded executor. Num threads: 16
Sending tick: 0...
Sending tick: 1...
Sending tick: 2...
Sending tick: 3...
Sending tick: 4...
Sending tick: 5...
<... omited>
Sending tick: 1399...
Sending tick: 1400...
Sending tick: 1401...
Sending tick: 1402...
Sending tick: 1403...
Sending tick: 1404...
Sending tick: 1405...
Sending tick: 1406...
Sending tick: 1407...
Sending tick: 1408...
<blocking here, it seems the timer callback is not called anymore>
thread apply all bt

chenlh gdb $ gdb
GNU gdb (Ubuntu 12.1-0ubuntu1~22.04) 12.1
Copyright (C) 2022 Free Software Foundation, Inc.
License GPLv3+: GNU GPL version 3 or later <http://gnu.org/licenses/gpl.html>
This is free software: you are free to change and redistribute it.
There is NO WARRANTY, to the extent permitted by law.
Type "show copying" and "show warranty" for details.
This GDB was configured as "x86_64-linux-gnu".
Type "show configuration" for configuration details.
For bug reporting instructions, please see:
<https://www.gnu.org/software/gdb/bugs/>.
Find the GDB manual and other documentation resources online at:
    <http://www.gnu.org/software/gdb/documentation/>.

For help, type "help".
Type "apropos word" to search for commands related to "word".
(gdb) attach 1526191
Attaching to process 1526191
[New LWP 1526192]
[New LWP 1526193]
[New LWP 1526194]
[New LWP 1526195]
[New LWP 1526196]
[New LWP 1526197]
[New LWP 1526198]
[New LWP 1526199]
[New LWP 1526200]
[New LWP 1526201]
[New LWP 1526202]
[New LWP 1526203]
[New LWP 1526204]
[New LWP 1526205]
[New LWP 1526206]
[New LWP 1526207]
[New LWP 1526208]
[New LWP 1526209]
[New LWP 1526210]
[New LWP 1526211]
[New LWP 1526212]
[New LWP 1526213]
[New LWP 1526214]
[New LWP 1526215]
[New LWP 1526216]
[New LWP 1526217]
[New LWP 1526218]
[Thread debugging using libthread_db enabled]
Using host libthread_db library "/lib/x86_64-linux-gnu/libthread_db.so.1".
futex_wait (private=0, expected=2, futex_word=0x7ffdd8094ce0) at ../sysdeps/nptl/futex-internal.h:146
146	../sysdeps/nptl/futex-internal.h: No such file or directory.
(gdb) thread apply all bt

Thread 28 (Thread 0x7f80a87f8640 (LWP 1526218) "publisher_membe"):
#0  futex_wait (private=0, expected=2, futex_word=0x7ffdd8094ce0) at ../sysdeps/nptl/futex-internal.h:146
#1  __GI___lll_lock_wait (futex=futex@entry=0x7ffdd8094ce0, private=0) at ./nptl/lowlevellock.c:49
#2  0x00007f80c4c27082 in lll_mutex_lock_optimized (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:48
#3  ___pthread_mutex_lock (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:93
#4  0x00007f80c5a84a01 in __gthread_mutex_lock (__mutex=0x7ffdd8094ce0) at /usr/include/x86_64-linux-gnu/c++/11/bits/gthr-default.h:749
#5  0x00007f80c5a872b2 in std::mutex::lock (this=0x7ffdd8094ce0) at /usr/include/c++/11/bits/std_mutex.h:100
#6  0x00007f80c5a87900 in std::lock_guard<std::mutex>::lock_guard (this=0x7f80a87f6ca8, __m=...) at /usr/include/c++/11/bits/std_mutex.h:229
#7  0x00007f80c5ac7169 in rclcpp::executors::MultiThreadedExecutor::run (this=0x7ffdd8094aa0, this_thread_number=14) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp:81
#8  0x00007f80c5ac92bd in std::__invoke_impl<void, void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__f=@0x55c5dc865a58: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>, __t=@0x55c5dc865a70: 0x7ffdd8094aa0) at /usr/include/c++/11/bits/invoke.h:74
#9  0x00007f80c5ac91cf in std::__invoke<void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__fn=@0x55c5dc865a58: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>) at /usr/include/c++/11/bits/invoke.h:96
#10 0x00007f80c5ac90d8 in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::__call<void, , 0ul, 1ul>(std::tuple<>&&, std::_Index_tuple<0ul, 1ul>) (this=0x55c5dc865a58, __args=...) at /usr/include/c++/11/functional:420
#11 0x00007f80c5ac901b in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::operator()<, void>() (this=0x55c5dc865a58) at /usr/include/c++/11/functional:503
#12 0x00007f80c5ac8fc2 in std::__invoke_impl<void, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::__invoke_other, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__f=...) at /usr/include/c++/11/bits/invoke.h:61
#13 0x00007f80c5ac8f6b in std::__invoke<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__fn=...) at /usr/include/c++/11/bits/invoke.h:96
#14 0x00007f80c5ac8f0c in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::_M_invoke<0ul>(std::_Index_tuple<0ul>) (this=0x55c5dc865a58) at /usr/include/c++/11/bits/std_thread.h:253
#15 0x00007f80c5ac8edc in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::operator()() (this=0x55c5dc865a58) at /usr/include/c++/11/bits/std_thread.h:260
#16 0x00007f80c5ac8ebc in std::thread::_State_impl<std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > > >::_M_run() (this=0x55c5dc865a50) at /usr/include/c++/11/bits/std_thread.h:211
#17 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#18 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#19 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81
--Type <RET> for more, q to quit, c to continue without paging--c

Thread 27 (Thread 0x7f80a8ff9640 (LWP 1526217) "publisher_membe"):
#0  futex_wait (private=0, expected=2, futex_word=0x7ffdd8094ce0) at ../sysdeps/nptl/futex-internal.h:146
#1  __GI___lll_lock_wait (futex=futex@entry=0x7ffdd8094ce0, private=0) at ./nptl/lowlevellock.c:49
#2  0x00007f80c4c27082 in lll_mutex_lock_optimized (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:48
#3  ___pthread_mutex_lock (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:93
#4  0x00007f80c5a84a01 in __gthread_mutex_lock (__mutex=0x7ffdd8094ce0) at /usr/include/x86_64-linux-gnu/c++/11/bits/gthr-default.h:749
#5  0x00007f80c5a872b2 in std::mutex::lock (this=0x7ffdd8094ce0) at /usr/include/c++/11/bits/std_mutex.h:100
#6  0x00007f80c5a87900 in std::lock_guard<std::mutex>::lock_guard (this=0x7f80a8ff7ca8, __m=...) at /usr/include/c++/11/bits/std_mutex.h:229
#7  0x00007f80c5ac7169 in rclcpp::executors::MultiThreadedExecutor::run (this=0x7ffdd8094aa0, this_thread_number=13) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp:81
#8  0x00007f80c5ac92bd in std::__invoke_impl<void, void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__f=@0x55c5dc865898: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>, __t=@0x55c5dc8658b0: 0x7ffdd8094aa0) at /usr/include/c++/11/bits/invoke.h:74
#9  0x00007f80c5ac91cf in std::__invoke<void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__fn=@0x55c5dc865898: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>) at /usr/include/c++/11/bits/invoke.h:96
#10 0x00007f80c5ac90d8 in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::__call<void, , 0ul, 1ul>(std::tuple<>&&, std::_Index_tuple<0ul, 1ul>) (this=0x55c5dc865898, __args=...) at /usr/include/c++/11/functional:420
#11 0x00007f80c5ac901b in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::operator()<, void>() (this=0x55c5dc865898) at /usr/include/c++/11/functional:503
#12 0x00007f80c5ac8fc2 in std::__invoke_impl<void, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::__invoke_other, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__f=...) at /usr/include/c++/11/bits/invoke.h:61
#13 0x00007f80c5ac8f6b in std::__invoke<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__fn=...) at /usr/include/c++/11/bits/invoke.h:96
#14 0x00007f80c5ac8f0c in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::_M_invoke<0ul>(std::_Index_tuple<0ul>) (this=0x55c5dc865898) at /usr/include/c++/11/bits/std_thread.h:253
#15 0x00007f80c5ac8edc in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::operator()() (this=0x55c5dc865898) at /usr/include/c++/11/bits/std_thread.h:260
#16 0x00007f80c5ac8ebc in std::thread::_State_impl<std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > > >::_M_run() (this=0x55c5dc865890) at /usr/include/c++/11/bits/std_thread.h:211
#17 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#18 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#19 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 26 (Thread 0x7f80a97fa640 (LWP 1526216) "publisher_membe"):
#0  futex_wait (private=0, expected=2, futex_word=0x7ffdd8094ce0) at ../sysdeps/nptl/futex-internal.h:146
#1  __GI___lll_lock_wait (futex=futex@entry=0x7ffdd8094ce0, private=0) at ./nptl/lowlevellock.c:49
#2  0x00007f80c4c27082 in lll_mutex_lock_optimized (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:48
#3  ___pthread_mutex_lock (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:93
#4  0x00007f80c5a84a01 in __gthread_mutex_lock (__mutex=0x7ffdd8094ce0) at /usr/include/x86_64-linux-gnu/c++/11/bits/gthr-default.h:749
#5  0x00007f80c5a872b2 in std::mutex::lock (this=0x7ffdd8094ce0) at /usr/include/c++/11/bits/std_mutex.h:100
#6  0x00007f80c5a87900 in std::lock_guard<std::mutex>::lock_guard (this=0x7f80a97f8ca8, __m=...) at /usr/include/c++/11/bits/std_mutex.h:229
#7  0x00007f80c5ac7169 in rclcpp::executors::MultiThreadedExecutor::run (this=0x7ffdd8094aa0, this_thread_number=12) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp:81
#8  0x00007f80c5ac92bd in std::__invoke_impl<void, void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__f=@0x55c5dc8656d8: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>, __t=@0x55c5dc8656f0: 0x7ffdd8094aa0) at /usr/include/c++/11/bits/invoke.h:74
#9  0x00007f80c5ac91cf in std::__invoke<void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__fn=@0x55c5dc8656d8: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>) at /usr/include/c++/11/bits/invoke.h:96
#10 0x00007f80c5ac90d8 in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::__call<void, , 0ul, 1ul>(std::tuple<>&&, std::_Index_tuple<0ul, 1ul>) (this=0x55c5dc8656d8, __args=...) at /usr/include/c++/11/functional:420
#11 0x00007f80c5ac901b in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::operator()<, void>() (this=0x55c5dc8656d8) at /usr/include/c++/11/functional:503
#12 0x00007f80c5ac8fc2 in std::__invoke_impl<void, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::__invoke_other, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__f=...) at /usr/include/c++/11/bits/invoke.h:61
#13 0x00007f80c5ac8f6b in std::__invoke<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__fn=...) at /usr/include/c++/11/bits/invoke.h:96
#14 0x00007f80c5ac8f0c in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::_M_invoke<0ul>(std::_Index_tuple<0ul>) (this=0x55c5dc8656d8) at /usr/include/c++/11/bits/std_thread.h:253
#15 0x00007f80c5ac8edc in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::operator()() (this=0x55c5dc8656d8) at /usr/include/c++/11/bits/std_thread.h:260
#16 0x00007f80c5ac8ebc in std::thread::_State_impl<std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > > >::_M_run() (this=0x55c5dc8656d0) at /usr/include/c++/11/bits/std_thread.h:211
#17 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#18 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#19 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 25 (Thread 0x7f80a9ffb640 (LWP 1526215) "publisher_membe"):
#0  __futex_abstimed_wait_common64 (private=0, cancel=true, abstime=0x0, op=393, expected=0, futex_word=0x55c5dc863a20) at ./nptl/futex-internal.c:57
#1  __futex_abstimed_wait_common (cancel=true, private=0, abstime=0x0, clockid=0, expected=0, futex_word=0x55c5dc863a20) at ./nptl/futex-internal.c:87
#2  __GI___futex_abstimed_wait_cancelable64 (futex_word=futex_word@entry=0x55c5dc863a20, expected=expected@entry=0, clockid=clockid@entry=0, abstime=abstime@entry=0x0, private=private@entry=0) at ./nptl/futex-internal.c:139
#3  0x00007f80c4c22ac1 in __pthread_cond_wait_common (abstime=0x0, clockid=0, mutex=0x55c5dc8639d0, cond=0x55c5dc8639f8) at ./nptl/pthread_cond_wait.c:503
#4  ___pthread_cond_wait (cond=0x55c5dc8639f8, mutex=0x55c5dc8639d0) at ./nptl/pthread_cond_wait.c:627
#5  0x00007f80c2ddf8a9 in std::condition_variable::wait<eprosima::fastdds::dds::detail::WaitSetImpl::wait(eprosima::fastdds::dds::ConditionSeq&, const Duration_t&)::<lambda()> >(std::unique_lock<std::mutex> &, struct {...}) (this=0x55c5dc8639f8, __lock=..., __p=...) at /usr/include/c++/11/condition_variable:103
#6  0x00007f80c2ddf5b3 in eprosima::fastdds::dds::detail::WaitSetImpl::wait (this=0x55c5dc8639d0, active_conditions=std::vector of length 0, capacity 0, timeout=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/fastdds/core/condition/WaitSetImpl.cpp:131
#7  0x00007f80c2ddc59e in eprosima::fastdds::dds::WaitSet::wait (this=0x55c5dc84fa30, active_conditions=std::vector of length 0, capacity 0, timeout=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/fastdds/core/condition/WaitSet.cpp:56
#8  0x00007f80c36e3350 in rmw_fastrtps_shared_cpp::__rmw_wait (identifier=0x7f80c37b6086 "rmw_fastrtps_cpp", subscriptions=0x55c5dc863408, guard_conditions=0x55c5dc863420, services=0x55c5dc863450, clients=0x55c5dc863438, events=0x55c5dc863468, wait_set=0x55c5dc8632d0, wait_timeout=0x0) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/rmw_wait.cpp:127
#9  0x00007f80c37aa096 in rmw_wait (subscriptions=0x55c5dc863408, guard_conditions=0x55c5dc863420, services=0x55c5dc863450, clients=0x55c5dc863438, events=0x55c5dc863468, wait_set=0x55c5dc8632d0, wait_timeout=0x0) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rmw_fastrtps/rmw_fastrtps_cpp/src/rmw_wait.cpp:33
#10 0x00007f80c4b4fecc in rmw_wait (v7=0x55c5dc863408, v6=0x55c5dc863420, v5=0x55c5dc863450, v4=0x55c5dc863438, v3=0x55c5dc863468, v2=0x55c5dc8632d0, v1=0x0) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rmw_implementation/rmw_implementation/src/functions.cpp:578
#11 0x00007f80c50b8dc6 in rcl_wait (wait_set=0x7ffdd8094b48, timeout=-1) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rcl/rcl/src/rcl/wait.c:595
#12 0x00007f80c5aba8c7 in rclcpp::Executor::wait_for_work (this=0x7ffdd8094aa0, timeout=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/executor.cpp:756
#13 0x00007f80c5abb5ba in rclcpp::Executor::get_next_executable (this=0x7ffdd8094aa0, any_executable=..., timeout=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/executor.cpp:912
#14 0x00007f80c5ac7217 in rclcpp::executors::MultiThreadedExecutor::run (this=0x7ffdd8094aa0, this_thread_number=11) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp:85
#15 0x00007f80c5ac92bd in std::__invoke_impl<void, void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__f=@0x55c5dc865518: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>, __t=@0x55c5dc865530: 0x7ffdd8094aa0) at /usr/include/c++/11/bits/invoke.h:74
#16 0x00007f80c5ac91cf in std::__invoke<void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__fn=@0x55c5dc865518: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>) at /usr/include/c++/11/bits/invoke.h:96
#17 0x00007f80c5ac90d8 in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::__call<void, , 0ul, 1ul>(std::tuple<>&&, std::_Index_tuple<0ul, 1ul>) (this=0x55c5dc865518, __args=...) at /usr/include/c++/11/functional:420
#18 0x00007f80c5ac901b in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::operator()<, void>() (this=0x55c5dc865518) at /usr/include/c++/11/functional:503
#19 0x00007f80c5ac8fc2 in std::__invoke_impl<void, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::__invoke_other, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__f=...) at /usr/include/c++/11/bits/invoke.h:61
#20 0x00007f80c5ac8f6b in std::__invoke<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__fn=...) at /usr/include/c++/11/bits/invoke.h:96
#21 0x00007f80c5ac8f0c in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::_M_invoke<0ul>(std::_Index_tuple<0ul>) (this=0x55c5dc865518) at /usr/include/c++/11/bits/std_thread.h:253
#22 0x00007f80c5ac8edc in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::operator()() (this=0x55c5dc865518) at /usr/include/c++/11/bits/std_thread.h:260
#23 0x00007f80c5ac8ebc in std::thread::_State_impl<std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > > >::_M_run() (this=0x55c5dc865510) at /usr/include/c++/11/bits/std_thread.h:211
#24 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#25 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#26 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 24 (Thread 0x7f80aa7fc640 (LWP 1526214) "publisher_membe"):
#0  futex_wait (private=0, expected=2, futex_word=0x7ffdd8094ce0) at ../sysdeps/nptl/futex-internal.h:146
#1  __GI___lll_lock_wait (futex=futex@entry=0x7ffdd8094ce0, private=0) at ./nptl/lowlevellock.c:49
#2  0x00007f80c4c27082 in lll_mutex_lock_optimized (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:48
#3  ___pthread_mutex_lock (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:93
#4  0x00007f80c5a84a01 in __gthread_mutex_lock (__mutex=0x7ffdd8094ce0) at /usr/include/x86_64-linux-gnu/c++/11/bits/gthr-default.h:749
#5  0x00007f80c5a872b2 in std::mutex::lock (this=0x7ffdd8094ce0) at /usr/include/c++/11/bits/std_mutex.h:100
#6  0x00007f80c5a87900 in std::lock_guard<std::mutex>::lock_guard (this=0x7f80aa7faca8, __m=...) at /usr/include/c++/11/bits/std_mutex.h:229
#7  0x00007f80c5ac7169 in rclcpp::executors::MultiThreadedExecutor::run (this=0x7ffdd8094aa0, this_thread_number=10) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp:81
#8  0x00007f80c5ac92bd in std::__invoke_impl<void, void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__f=@0x55c5dc865358: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>, __t=@0x55c5dc865370: 0x7ffdd8094aa0) at /usr/include/c++/11/bits/invoke.h:74
#9  0x00007f80c5ac91cf in std::__invoke<void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__fn=@0x55c5dc865358: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>) at /usr/include/c++/11/bits/invoke.h:96
#10 0x00007f80c5ac90d8 in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::__call<void, , 0ul, 1ul>(std::tuple<>&&, std::_Index_tuple<0ul, 1ul>) (this=0x55c5dc865358, __args=...) at /usr/include/c++/11/functional:420
#11 0x00007f80c5ac901b in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::operator()<, void>() (this=0x55c5dc865358) at /usr/include/c++/11/functional:503
#12 0x00007f80c5ac8fc2 in std::__invoke_impl<void, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::__invoke_other, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__f=...) at /usr/include/c++/11/bits/invoke.h:61
#13 0x00007f80c5ac8f6b in std::__invoke<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__fn=...) at /usr/include/c++/11/bits/invoke.h:96
#14 0x00007f80c5ac8f0c in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::_M_invoke<0ul>(std::_Index_tuple<0ul>) (this=0x55c5dc865358) at /usr/include/c++/11/bits/std_thread.h:253
#15 0x00007f80c5ac8edc in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::operator()() (this=0x55c5dc865358) at /usr/include/c++/11/bits/std_thread.h:260
#16 0x00007f80c5ac8ebc in std::thread::_State_impl<std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > > >::_M_run() (this=0x55c5dc865350) at /usr/include/c++/11/bits/std_thread.h:211
#17 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#18 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#19 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 23 (Thread 0x7f80aaffd640 (LWP 1526213) "publisher_membe"):
#0  futex_wait (private=0, expected=2, futex_word=0x7ffdd8094ce0) at ../sysdeps/nptl/futex-internal.h:146
#1  __GI___lll_lock_wait (futex=futex@entry=0x7ffdd8094ce0, private=0) at ./nptl/lowlevellock.c:49
#2  0x00007f80c4c27082 in lll_mutex_lock_optimized (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:48
#3  ___pthread_mutex_lock (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:93
#4  0x00007f80c5a84a01 in __gthread_mutex_lock (__mutex=0x7ffdd8094ce0) at /usr/include/x86_64-linux-gnu/c++/11/bits/gthr-default.h:749
#5  0x00007f80c5a872b2 in std::mutex::lock (this=0x7ffdd8094ce0) at /usr/include/c++/11/bits/std_mutex.h:100
#6  0x00007f80c5a87900 in std::lock_guard<std::mutex>::lock_guard (this=0x7f80aaffbca8, __m=...) at /usr/include/c++/11/bits/std_mutex.h:229
#7  0x00007f80c5ac7169 in rclcpp::executors::MultiThreadedExecutor::run (this=0x7ffdd8094aa0, this_thread_number=9) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp:81
#8  0x00007f80c5ac92bd in std::__invoke_impl<void, void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__f=@0x55c5dc865198: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>, __t=@0x55c5dc8651b0: 0x7ffdd8094aa0) at /usr/include/c++/11/bits/invoke.h:74
#9  0x00007f80c5ac91cf in std::__invoke<void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__fn=@0x55c5dc865198: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>) at /usr/include/c++/11/bits/invoke.h:96
#10 0x00007f80c5ac90d8 in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::__call<void, , 0ul, 1ul>(std::tuple<>&&, std::_Index_tuple<0ul, 1ul>) (this=0x55c5dc865198, __args=...) at /usr/include/c++/11/functional:420
#11 0x00007f80c5ac901b in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::operator()<, void>() (this=0x55c5dc865198) at /usr/include/c++/11/functional:503
#12 0x00007f80c5ac8fc2 in std::__invoke_impl<void, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::__invoke_other, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__f=...) at /usr/include/c++/11/bits/invoke.h:61
#13 0x00007f80c5ac8f6b in std::__invoke<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__fn=...) at /usr/include/c++/11/bits/invoke.h:96
#14 0x00007f80c5ac8f0c in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::_M_invoke<0ul>(std::_Index_tuple<0ul>) (this=0x55c5dc865198) at /usr/include/c++/11/bits/std_thread.h:253
#15 0x00007f80c5ac8edc in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::operator()() (this=0x55c5dc865198) at /usr/include/c++/11/bits/std_thread.h:260
#16 0x00007f80c5ac8ebc in std::thread::_State_impl<std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > > >::_M_run() (this=0x55c5dc865190) at /usr/include/c++/11/bits/std_thread.h:211
#17 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#18 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#19 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 22 (Thread 0x7f80ab7fe640 (LWP 1526212) "publisher_membe"):
#0  futex_wait (private=0, expected=2, futex_word=0x7ffdd8094ce0) at ../sysdeps/nptl/futex-internal.h:146
#1  __GI___lll_lock_wait (futex=futex@entry=0x7ffdd8094ce0, private=0) at ./nptl/lowlevellock.c:49
#2  0x00007f80c4c27082 in lll_mutex_lock_optimized (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:48
#3  ___pthread_mutex_lock (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:93
#4  0x00007f80c5a84a01 in __gthread_mutex_lock (__mutex=0x7ffdd8094ce0) at /usr/include/x86_64-linux-gnu/c++/11/bits/gthr-default.h:749
#5  0x00007f80c5a872b2 in std::mutex::lock (this=0x7ffdd8094ce0) at /usr/include/c++/11/bits/std_mutex.h:100
#6  0x00007f80c5a87900 in std::lock_guard<std::mutex>::lock_guard (this=0x7f80ab7fcca8, __m=...) at /usr/include/c++/11/bits/std_mutex.h:229
#7  0x00007f80c5ac7169 in rclcpp::executors::MultiThreadedExecutor::run (this=0x7ffdd8094aa0, this_thread_number=8) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp:81
#8  0x00007f80c5ac92bd in std::__invoke_impl<void, void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__f=@0x55c5dc864fd8: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>, __t=@0x55c5dc864ff0: 0x7ffdd8094aa0) at /usr/include/c++/11/bits/invoke.h:74
#9  0x00007f80c5ac91cf in std::__invoke<void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__fn=@0x55c5dc864fd8: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>) at /usr/include/c++/11/bits/invoke.h:96
#10 0x00007f80c5ac90d8 in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::__call<void, , 0ul, 1ul>(std::tuple<>&&, std::_Index_tuple<0ul, 1ul>) (this=0x55c5dc864fd8, __args=...) at /usr/include/c++/11/functional:420
#11 0x00007f80c5ac901b in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::operator()<, void>() (this=0x55c5dc864fd8) at /usr/include/c++/11/functional:503
#12 0x00007f80c5ac8fc2 in std::__invoke_impl<void, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::__invoke_other, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__f=...) at /usr/include/c++/11/bits/invoke.h:61
#13 0x00007f80c5ac8f6b in std::__invoke<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__fn=...) at /usr/include/c++/11/bits/invoke.h:96
#14 0x00007f80c5ac8f0c in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::_M_invoke<0ul>(std::_Index_tuple<0ul>) (this=0x55c5dc864fd8) at /usr/include/c++/11/bits/std_thread.h:253
#15 0x00007f80c5ac8edc in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::operator()() (this=0x55c5dc864fd8) at /usr/include/c++/11/bits/std_thread.h:260
#16 0x00007f80c5ac8ebc in std::thread::_State_impl<std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > > >::_M_run() (this=0x55c5dc864fd0) at /usr/include/c++/11/bits/std_thread.h:211
#17 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#18 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#19 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 21 (Thread 0x7f80abfff640 (LWP 1526211) "publisher_membe"):
#0  futex_wait (private=0, expected=2, futex_word=0x7ffdd8094ce0) at ../sysdeps/nptl/futex-internal.h:146
#1  __GI___lll_lock_wait (futex=futex@entry=0x7ffdd8094ce0, private=0) at ./nptl/lowlevellock.c:49
#2  0x00007f80c4c27082 in lll_mutex_lock_optimized (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:48
#3  ___pthread_mutex_lock (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:93
#4  0x00007f80c5a84a01 in __gthread_mutex_lock (__mutex=0x7ffdd8094ce0) at /usr/include/x86_64-linux-gnu/c++/11/bits/gthr-default.h:749
#5  0x00007f80c5a872b2 in std::mutex::lock (this=0x7ffdd8094ce0) at /usr/include/c++/11/bits/std_mutex.h:100
#6  0x00007f80c5a87900 in std::lock_guard<std::mutex>::lock_guard (this=0x7f80abffdca8, __m=...) at /usr/include/c++/11/bits/std_mutex.h:229
#7  0x00007f80c5ac7169 in rclcpp::executors::MultiThreadedExecutor::run (this=0x7ffdd8094aa0, this_thread_number=7) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp:81
#8  0x00007f80c5ac92bd in std::__invoke_impl<void, void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__f=@0x55c5dc864d88: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>, __t=@0x55c5dc864da0: 0x7ffdd8094aa0) at /usr/include/c++/11/bits/invoke.h:74
#9  0x00007f80c5ac91cf in std::__invoke<void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__fn=@0x55c5dc864d88: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>) at /usr/include/c++/11/bits/invoke.h:96
#10 0x00007f80c5ac90d8 in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::__call<void, , 0ul, 1ul>(std::tuple<>&&, std::_Index_tuple<0ul, 1ul>) (this=0x55c5dc864d88, __args=...) at /usr/include/c++/11/functional:420
#11 0x00007f80c5ac901b in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::operator()<, void>() (this=0x55c5dc864d88) at /usr/include/c++/11/functional:503
#12 0x00007f80c5ac8fc2 in std::__invoke_impl<void, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::__invoke_other, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__f=...) at /usr/include/c++/11/bits/invoke.h:61
#13 0x00007f80c5ac8f6b in std::__invoke<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__fn=...) at /usr/include/c++/11/bits/invoke.h:96
#14 0x00007f80c5ac8f0c in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::_M_invoke<0ul>(std::_Index_tuple<0ul>) (this=0x55c5dc864d88) at /usr/include/c++/11/bits/std_thread.h:253
#15 0x00007f80c5ac8edc in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::operator()() (this=0x55c5dc864d88) at /usr/include/c++/11/bits/std_thread.h:260
#16 0x00007f80c5ac8ebc in std::thread::_State_impl<std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > > >::_M_run() (this=0x55c5dc864d80) at /usr/include/c++/11/bits/std_thread.h:211
#17 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#18 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#19 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 20 (Thread 0x7f80b0ff9640 (LWP 1526210) "publisher_membe"):
#0  futex_wait (private=0, expected=2, futex_word=0x7ffdd8094ce0) at ../sysdeps/nptl/futex-internal.h:146
#1  __GI___lll_lock_wait (futex=futex@entry=0x7ffdd8094ce0, private=0) at ./nptl/lowlevellock.c:49
#2  0x00007f80c4c27082 in lll_mutex_lock_optimized (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:48
#3  ___pthread_mutex_lock (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:93
#4  0x00007f80c5a84a01 in __gthread_mutex_lock (__mutex=0x7ffdd8094ce0) at /usr/include/x86_64-linux-gnu/c++/11/bits/gthr-default.h:749
#5  0x00007f80c5a872b2 in std::mutex::lock (this=0x7ffdd8094ce0) at /usr/include/c++/11/bits/std_mutex.h:100
#6  0x00007f80c5a87900 in std::lock_guard<std::mutex>::lock_guard (this=0x7f80b0ff7ca8, __m=...) at /usr/include/c++/11/bits/std_mutex.h:229
#7  0x00007f80c5ac7169 in rclcpp::executors::MultiThreadedExecutor::run (this=0x7ffdd8094aa0, this_thread_number=6) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp:81
#8  0x00007f80c5ac92bd in std::__invoke_impl<void, void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__f=@0x55c5dc864bc8: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>, __t=@0x55c5dc864be0: 0x7ffdd8094aa0) at /usr/include/c++/11/bits/invoke.h:74
#9  0x00007f80c5ac91cf in std::__invoke<void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__fn=@0x55c5dc864bc8: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>) at /usr/include/c++/11/bits/invoke.h:96
#10 0x00007f80c5ac90d8 in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::__call<void, , 0ul, 1ul>(std::tuple<>&&, std::_Index_tuple<0ul, 1ul>) (this=0x55c5dc864bc8, __args=...) at /usr/include/c++/11/functional:420
#11 0x00007f80c5ac901b in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::operator()<, void>() (this=0x55c5dc864bc8) at /usr/include/c++/11/functional:503
#12 0x00007f80c5ac8fc2 in std::__invoke_impl<void, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::__invoke_other, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__f=...) at /usr/include/c++/11/bits/invoke.h:61
#13 0x00007f80c5ac8f6b in std::__invoke<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__fn=...) at /usr/include/c++/11/bits/invoke.h:96
#14 0x00007f80c5ac8f0c in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::_M_invoke<0ul>(std::_Index_tuple<0ul>) (this=0x55c5dc864bc8) at /usr/include/c++/11/bits/std_thread.h:253
#15 0x00007f80c5ac8edc in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::operator()() (this=0x55c5dc864bc8) at /usr/include/c++/11/bits/std_thread.h:260
#16 0x00007f80c5ac8ebc in std::thread::_State_impl<std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > > >::_M_run() (this=0x55c5dc864bc0) at /usr/include/c++/11/bits/std_thread.h:211
#17 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#18 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#19 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 19 (Thread 0x7f80b17fa640 (LWP 1526209) "publisher_membe"):
#0  futex_wait (private=0, expected=2, futex_word=0x7ffdd8094ce0) at ../sysdeps/nptl/futex-internal.h:146
#1  __GI___lll_lock_wait (futex=futex@entry=0x7ffdd8094ce0, private=0) at ./nptl/lowlevellock.c:49
#2  0x00007f80c4c27082 in lll_mutex_lock_optimized (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:48
#3  ___pthread_mutex_lock (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:93
#4  0x00007f80c5a84a01 in __gthread_mutex_lock (__mutex=0x7ffdd8094ce0) at /usr/include/x86_64-linux-gnu/c++/11/bits/gthr-default.h:749
#5  0x00007f80c5a872b2 in std::mutex::lock (this=0x7ffdd8094ce0) at /usr/include/c++/11/bits/std_mutex.h:100
#6  0x00007f80c5a87900 in std::lock_guard<std::mutex>::lock_guard (this=0x7f80b17f8ca8, __m=...) at /usr/include/c++/11/bits/std_mutex.h:229
#7  0x00007f80c5ac7169 in rclcpp::executors::MultiThreadedExecutor::run (this=0x7ffdd8094aa0, this_thread_number=5) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp:81
#8  0x00007f80c5ac92bd in std::__invoke_impl<void, void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__f=@0x55c5dc864478: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>, __t=@0x55c5dc864490: 0x7ffdd8094aa0) at /usr/include/c++/11/bits/invoke.h:74
#9  0x00007f80c5ac91cf in std::__invoke<void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__fn=@0x55c5dc864478: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>) at /usr/include/c++/11/bits/invoke.h:96
#10 0x00007f80c5ac90d8 in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::__call<void, , 0ul, 1ul>(std::tuple<>&&, std::_Index_tuple<0ul, 1ul>) (this=0x55c5dc864478, __args=...) at /usr/include/c++/11/functional:420
#11 0x00007f80c5ac901b in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::operator()<, void>() (this=0x55c5dc864478) at /usr/include/c++/11/functional:503
#12 0x00007f80c5ac8fc2 in std::__invoke_impl<void, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::__invoke_other, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__f=...) at /usr/include/c++/11/bits/invoke.h:61
#13 0x00007f80c5ac8f6b in std::__invoke<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__fn=...) at /usr/include/c++/11/bits/invoke.h:96
#14 0x00007f80c5ac8f0c in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::_M_invoke<0ul>(std::_Index_tuple<0ul>) (this=0x55c5dc864478) at /usr/include/c++/11/bits/std_thread.h:253
#15 0x00007f80c5ac8edc in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::operator()() (this=0x55c5dc864478) at /usr/include/c++/11/bits/std_thread.h:260
#16 0x00007f80c5ac8ebc in std::thread::_State_impl<std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > > >::_M_run() (this=0x55c5dc864470) at /usr/include/c++/11/bits/std_thread.h:211
#17 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#18 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#19 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 18 (Thread 0x7f80b1ffb640 (LWP 1526208) "publisher_membe"):
#0  futex_wait (private=0, expected=2, futex_word=0x7ffdd8094ce0) at ../sysdeps/nptl/futex-internal.h:146
#1  __GI___lll_lock_wait (futex=futex@entry=0x7ffdd8094ce0, private=0) at ./nptl/lowlevellock.c:49
#2  0x00007f80c4c27082 in lll_mutex_lock_optimized (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:48
#3  ___pthread_mutex_lock (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:93
#4  0x00007f80c5a84a01 in __gthread_mutex_lock (__mutex=0x7ffdd8094ce0) at /usr/include/x86_64-linux-gnu/c++/11/bits/gthr-default.h:749
#5  0x00007f80c5a872b2 in std::mutex::lock (this=0x7ffdd8094ce0) at /usr/include/c++/11/bits/std_mutex.h:100
#6  0x00007f80c5a87900 in std::lock_guard<std::mutex>::lock_guard (this=0x7f80b1ff9ca8, __m=...) at /usr/include/c++/11/bits/std_mutex.h:229
#7  0x00007f80c5ac7169 in rclcpp::executors::MultiThreadedExecutor::run (this=0x7ffdd8094aa0, this_thread_number=4) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp:81
#8  0x00007f80c5ac92bd in std::__invoke_impl<void, void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__f=@0x55c5dc864878: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>, __t=@0x55c5dc864890: 0x7ffdd8094aa0) at /usr/include/c++/11/bits/invoke.h:74
#9  0x00007f80c5ac91cf in std::__invoke<void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__fn=@0x55c5dc864878: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>) at /usr/include/c++/11/bits/invoke.h:96
#10 0x00007f80c5ac90d8 in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::__call<void, , 0ul, 1ul>(std::tuple<>&&, std::_Index_tuple<0ul, 1ul>) (this=0x55c5dc864878, __args=...) at /usr/include/c++/11/functional:420
#11 0x00007f80c5ac901b in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::operator()<, void>() (this=0x55c5dc864878) at /usr/include/c++/11/functional:503
#12 0x00007f80c5ac8fc2 in std::__invoke_impl<void, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::__invoke_other, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__f=...) at /usr/include/c++/11/bits/invoke.h:61
#13 0x00007f80c5ac8f6b in std::__invoke<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__fn=...) at /usr/include/c++/11/bits/invoke.h:96
#14 0x00007f80c5ac8f0c in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::_M_invoke<0ul>(std::_Index_tuple<0ul>) (this=0x55c5dc864878) at /usr/include/c++/11/bits/std_thread.h:253
#15 0x00007f80c5ac8edc in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::operator()() (this=0x55c5dc864878) at /usr/include/c++/11/bits/std_thread.h:260
#16 0x00007f80c5ac8ebc in std::thread::_State_impl<std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > > >::_M_run() (this=0x55c5dc864870) at /usr/include/c++/11/bits/std_thread.h:211
#17 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#18 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#19 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 17 (Thread 0x7f80b27fc640 (LWP 1526207) "publisher_membe"):
#0  futex_wait (private=0, expected=2, futex_word=0x7ffdd8094ce0) at ../sysdeps/nptl/futex-internal.h:146
#1  __GI___lll_lock_wait (futex=futex@entry=0x7ffdd8094ce0, private=0) at ./nptl/lowlevellock.c:49
#2  0x00007f80c4c27082 in lll_mutex_lock_optimized (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:48
#3  ___pthread_mutex_lock (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:93
#4  0x00007f80c5a84a01 in __gthread_mutex_lock (__mutex=0x7ffdd8094ce0) at /usr/include/x86_64-linux-gnu/c++/11/bits/gthr-default.h:749
#5  0x00007f80c5a872b2 in std::mutex::lock (this=0x7ffdd8094ce0) at /usr/include/c++/11/bits/std_mutex.h:100
#6  0x00007f80c5a87900 in std::lock_guard<std::mutex>::lock_guard (this=0x7f80b27faca8, __m=...) at /usr/include/c++/11/bits/std_mutex.h:229
#7  0x00007f80c5ac7169 in rclcpp::executors::MultiThreadedExecutor::run (this=0x7ffdd8094aa0, this_thread_number=3) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp:81
#8  0x00007f80c5ac92bd in std::__invoke_impl<void, void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__f=@0x55c5dc864668: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>, __t=@0x55c5dc864680: 0x7ffdd8094aa0) at /usr/include/c++/11/bits/invoke.h:74
#9  0x00007f80c5ac91cf in std::__invoke<void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__fn=@0x55c5dc864668: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>) at /usr/include/c++/11/bits/invoke.h:96
#10 0x00007f80c5ac90d8 in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::__call<void, , 0ul, 1ul>(std::tuple<>&&, std::_Index_tuple<0ul, 1ul>) (this=0x55c5dc864668, __args=...) at /usr/include/c++/11/functional:420
#11 0x00007f80c5ac901b in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::operator()<, void>() (this=0x55c5dc864668) at /usr/include/c++/11/functional:503
#12 0x00007f80c5ac8fc2 in std::__invoke_impl<void, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::__invoke_other, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__f=...) at /usr/include/c++/11/bits/invoke.h:61
#13 0x00007f80c5ac8f6b in std::__invoke<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__fn=...) at /usr/include/c++/11/bits/invoke.h:96
#14 0x00007f80c5ac8f0c in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::_M_invoke<0ul>(std::_Index_tuple<0ul>) (this=0x55c5dc864668) at /usr/include/c++/11/bits/std_thread.h:253
#15 0x00007f80c5ac8edc in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::operator()() (this=0x55c5dc864668) at /usr/include/c++/11/bits/std_thread.h:260
#16 0x00007f80c5ac8ebc in std::thread::_State_impl<std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > > >::_M_run() (this=0x55c5dc864660) at /usr/include/c++/11/bits/std_thread.h:211
#17 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#18 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#19 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 16 (Thread 0x7f80b2ffd640 (LWP 1526206) "publisher_membe"):
#0  futex_wait (private=0, expected=2, futex_word=0x7ffdd8094ce0) at ../sysdeps/nptl/futex-internal.h:146
#1  __GI___lll_lock_wait (futex=futex@entry=0x7ffdd8094ce0, private=0) at ./nptl/lowlevellock.c:49
#2  0x00007f80c4c27082 in lll_mutex_lock_optimized (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:48
#3  ___pthread_mutex_lock (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:93
#4  0x00007f80c5a84a01 in __gthread_mutex_lock (__mutex=0x7ffdd8094ce0) at /usr/include/x86_64-linux-gnu/c++/11/bits/gthr-default.h:749
#5  0x00007f80c5a872b2 in std::mutex::lock (this=0x7ffdd8094ce0) at /usr/include/c++/11/bits/std_mutex.h:100
#6  0x00007f80c5a87900 in std::lock_guard<std::mutex>::lock_guard (this=0x7f80b2ffbca8, __m=...) at /usr/include/c++/11/bits/std_mutex.h:229
#7  0x00007f80c5ac7169 in rclcpp::executors::MultiThreadedExecutor::run (this=0x7ffdd8094aa0, this_thread_number=2) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp:81
#8  0x00007f80c5ac92bd in std::__invoke_impl<void, void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__f=@0x55c5dc8644a8: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>, __t=@0x55c5dc8644c0: 0x7ffdd8094aa0) at /usr/include/c++/11/bits/invoke.h:74
#9  0x00007f80c5ac91cf in std::__invoke<void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__fn=@0x55c5dc8644a8: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>) at /usr/include/c++/11/bits/invoke.h:96
#10 0x00007f80c5ac90d8 in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::__call<void, , 0ul, 1ul>(std::tuple<>&&, std::_Index_tuple<0ul, 1ul>) (this=0x55c5dc8644a8, __args=...) at /usr/include/c++/11/functional:420
#11 0x00007f80c5ac901b in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::operator()<, void>() (this=0x55c5dc8644a8) at /usr/include/c++/11/functional:503
#12 0x00007f80c5ac8fc2 in std::__invoke_impl<void, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::__invoke_other, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__f=...) at /usr/include/c++/11/bits/invoke.h:61
#13 0x00007f80c5ac8f6b in std::__invoke<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__fn=...) at /usr/include/c++/11/bits/invoke.h:96
#14 0x00007f80c5ac8f0c in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::_M_invoke<0ul>(std::_Index_tuple<0ul>) (this=0x55c5dc8644a8) at /usr/include/c++/11/bits/std_thread.h:253
#15 0x00007f80c5ac8edc in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::operator()() (this=0x55c5dc8644a8) at /usr/include/c++/11/bits/std_thread.h:260
#16 0x00007f80c5ac8ebc in std::thread::_State_impl<std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > > >::_M_run() (this=0x55c5dc8644a0) at /usr/include/c++/11/bits/std_thread.h:211
#17 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#18 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#19 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 15 (Thread 0x7f80b37fe640 (LWP 1526205) "publisher_membe"):
#0  futex_wait (private=0, expected=2, futex_word=0x7ffdd8094ce0) at ../sysdeps/nptl/futex-internal.h:146
#1  __GI___lll_lock_wait (futex=futex@entry=0x7ffdd8094ce0, private=0) at ./nptl/lowlevellock.c:49
#2  0x00007f80c4c27082 in lll_mutex_lock_optimized (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:48
#3  ___pthread_mutex_lock (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:93
#4  0x00007f80c5a84a01 in __gthread_mutex_lock (__mutex=0x7ffdd8094ce0) at /usr/include/x86_64-linux-gnu/c++/11/bits/gthr-default.h:749
#5  0x00007f80c5a872b2 in std::mutex::lock (this=0x7ffdd8094ce0) at /usr/include/c++/11/bits/std_mutex.h:100
#6  0x00007f80c5a87900 in std::lock_guard<std::mutex>::lock_guard (this=0x7f80b37fcca8, __m=...) at /usr/include/c++/11/bits/std_mutex.h:229
#7  0x00007f80c5ac7169 in rclcpp::executors::MultiThreadedExecutor::run (this=0x7ffdd8094aa0, this_thread_number=1) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp:81
#8  0x00007f80c5ac92bd in std::__invoke_impl<void, void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__f=@0x55c5dc8642b8: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>, __t=@0x55c5dc8642d0: 0x7ffdd8094aa0) at /usr/include/c++/11/bits/invoke.h:74
#9  0x00007f80c5ac91cf in std::__invoke<void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__fn=@0x55c5dc8642b8: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>) at /usr/include/c++/11/bits/invoke.h:96
#10 0x00007f80c5ac90d8 in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::__call<void, , 0ul, 1ul>(std::tuple<>&&, std::_Index_tuple<0ul, 1ul>) (this=0x55c5dc8642b8, __args=...) at /usr/include/c++/11/functional:420
#11 0x00007f80c5ac901b in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::operator()<, void>() (this=0x55c5dc8642b8) at /usr/include/c++/11/functional:503
#12 0x00007f80c5ac8fc2 in std::__invoke_impl<void, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::__invoke_other, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__f=...) at /usr/include/c++/11/bits/invoke.h:61
#13 0x00007f80c5ac8f6b in std::__invoke<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__fn=...) at /usr/include/c++/11/bits/invoke.h:96
#14 0x00007f80c5ac8f0c in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::_M_invoke<0ul>(std::_Index_tuple<0ul>) (this=0x55c5dc8642b8) at /usr/include/c++/11/bits/std_thread.h:253
#15 0x00007f80c5ac8edc in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::operator()() (this=0x55c5dc8642b8) at /usr/include/c++/11/bits/std_thread.h:260
#16 0x00007f80c5ac8ebc in std::thread::_State_impl<std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > > >::_M_run() (this=0x55c5dc8642b0) at /usr/include/c++/11/bits/std_thread.h:211
#17 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#18 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#19 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 14 (Thread 0x7f80b3fff640 (LWP 1526204) "publisher_membe"):
#0  futex_wait (private=0, expected=2, futex_word=0x7ffdd8094ce0) at ../sysdeps/nptl/futex-internal.h:146
#1  __GI___lll_lock_wait (futex=futex@entry=0x7ffdd8094ce0, private=0) at ./nptl/lowlevellock.c:49
#2  0x00007f80c4c27082 in lll_mutex_lock_optimized (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:48
#3  ___pthread_mutex_lock (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:93
#4  0x00007f80c5a84a01 in __gthread_mutex_lock (__mutex=0x7ffdd8094ce0) at /usr/include/x86_64-linux-gnu/c++/11/bits/gthr-default.h:749
#5  0x00007f80c5a872b2 in std::mutex::lock (this=0x7ffdd8094ce0) at /usr/include/c++/11/bits/std_mutex.h:100
#6  0x00007f80c5a87900 in std::lock_guard<std::mutex>::lock_guard (this=0x7f80b3ffdca8, __m=...) at /usr/include/c++/11/bits/std_mutex.h:229
#7  0x00007f80c5ac7169 in rclcpp::executors::MultiThreadedExecutor::run (this=0x7ffdd8094aa0, this_thread_number=0) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp:81
#8  0x00007f80c5ac92bd in std::__invoke_impl<void, void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__f=@0x55c5dc8640d8: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>, __t=@0x55c5dc8640f0: 0x7ffdd8094aa0) at /usr/include/c++/11/bits/invoke.h:74
#9  0x00007f80c5ac91cf in std::__invoke<void (rclcpp::executors::MultiThreadedExecutor::*&)(unsigned long), rclcpp::executors::MultiThreadedExecutor*&, unsigned long&> (__fn=@0x55c5dc8640d8: (void (rclcpp::executors::MultiThreadedExecutor::*)(rclcpp::executors::MultiThreadedExecutor * const, unsigned long)) 0x7f80c5ac7106 <rclcpp::executors::MultiThreadedExecutor::run(unsigned long)>) at /usr/include/c++/11/bits/invoke.h:96
#10 0x00007f80c5ac90d8 in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::__call<void, , 0ul, 1ul>(std::tuple<>&&, std::_Index_tuple<0ul, 1ul>) (this=0x55c5dc8640d8, __args=...) at /usr/include/c++/11/functional:420
#11 0x00007f80c5ac901b in std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>::operator()<, void>() (this=0x55c5dc8640d8) at /usr/include/c++/11/functional:503
#12 0x00007f80c5ac8fc2 in std::__invoke_impl<void, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::__invoke_other, std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__f=...) at /usr/include/c++/11/bits/invoke.h:61
#13 0x00007f80c5ac8f6b in std::__invoke<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>>(std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)>&&) (__fn=...) at /usr/include/c++/11/bits/invoke.h:96
#14 0x00007f80c5ac8f0c in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::_M_invoke<0ul>(std::_Index_tuple<0ul>) (this=0x55c5dc8640d8) at /usr/include/c++/11/bits/std_thread.h:253
#15 0x00007f80c5ac8edc in std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > >::operator()() (this=0x55c5dc8640d8) at /usr/include/c++/11/bits/std_thread.h:260
#16 0x00007f80c5ac8ebc in std::thread::_State_impl<std::thread::_Invoker<std::tuple<std::_Bind<void (rclcpp::executors::MultiThreadedExecutor::*(rclcpp::executors::MultiThreadedExecutor*, unsigned long))(unsigned long)> > > >::_M_run() (this=0x55c5dc8640d0) at /usr/include/c++/11/bits/std_thread.h:211
#17 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#18 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#19 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 13 (Thread 0x7f80b8f19640 (LWP 1526203) "publisher_membe"):
#0  __futex_abstimed_wait_common64 (private=0, cancel=true, abstime=0x0, op=393, expected=0, futex_word=0x7f80ac000c04) at ./nptl/futex-internal.c:57
#1  __futex_abstimed_wait_common (cancel=true, private=0, abstime=0x0, clockid=0, expected=0, futex_word=0x7f80ac000c04) at ./nptl/futex-internal.c:87
#2  __GI___futex_abstimed_wait_cancelable64 (futex_word=futex_word@entry=0x7f80ac000c04, expected=expected@entry=0, clockid=clockid@entry=0, abstime=abstime@entry=0x0, private=private@entry=0) at ./nptl/futex-internal.c:139
#3  0x00007f80c4c22ac1 in __pthread_cond_wait_common (abstime=0x0, clockid=0, mutex=0x7f80ac000bb0, cond=0x7f80ac000bd8) at ./nptl/pthread_cond_wait.c:503
#4  ___pthread_cond_wait (cond=0x7f80ac000bd8, mutex=0x7f80ac000bb0) at ./nptl/pthread_cond_wait.c:627
#5  0x00007f80c2ddf8a9 in std::condition_variable::wait<eprosima::fastdds::dds::detail::WaitSetImpl::wait(eprosima::fastdds::dds::ConditionSeq&, const Duration_t&)::<lambda()> >(std::unique_lock<std::mutex> &, struct {...}) (this=0x7f80ac000bd8, __lock=..., __p=...) at /usr/include/c++/11/condition_variable:103
#6  0x00007f80c2ddf5b3 in eprosima::fastdds::dds::detail::WaitSetImpl::wait (this=0x7f80ac000bb0, active_conditions=std::vector of length 0, capacity 0, timeout=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/fastdds/core/condition/WaitSetImpl.cpp:131
#7  0x00007f80c2ddc59e in eprosima::fastdds::dds::WaitSet::wait (this=0x7f80ac000b90, active_conditions=std::vector of length 0, capacity 0, timeout=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/fastdds/core/condition/WaitSet.cpp:56
#8  0x00007f80c36e3350 in rmw_fastrtps_shared_cpp::__rmw_wait (identifier=0x7f80c37b6086 "rmw_fastrtps_cpp", subscriptions=0x7f80b8f17da0, guard_conditions=0x7f80b8f17db0, services=0x0, clients=0x0, events=0x0, wait_set=0x7f80ac000b70, wait_timeout=0x0) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/rmw_wait.cpp:127
#9  0x00007f80c367e3bd in node_listener (context=0x55c5dc5e2850) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/listener_thread.cpp:142
#10 0x00007f80c367f2f2 in std::__invoke_impl<void, void (*)(rmw_context_s*), rmw_context_s*> (__f=@0x55c5dc7236a0: 0x7f80c367e181 <node_listener(rmw_context_t*)>) at /usr/include/c++/11/bits/invoke.h:61
#11 0x00007f80c367f253 in std::__invoke<void (*)(rmw_context_s*), rmw_context_s*> (__fn=@0x55c5dc7236a0: 0x7f80c367e181 <node_listener(rmw_context_t*)>) at /usr/include/c++/11/bits/invoke.h:96
#12 0x00007f80c367f1b3 in std::thread::_Invoker<std::tuple<void (*)(rmw_context_s*), rmw_context_s*> >::_M_invoke<0ul, 1ul> (this=0x55c5dc723698) at /usr/include/c++/11/bits/std_thread.h:253
#13 0x00007f80c367f168 in std::thread::_Invoker<std::tuple<void (*)(rmw_context_s*), rmw_context_s*> >::operator() (this=0x55c5dc723698) at /usr/include/c++/11/bits/std_thread.h:260
#14 0x00007f80c367f148 in std::thread::_State_impl<std::thread::_Invoker<std::tuple<void (*)(rmw_context_s*), rmw_context_s*> > >::_M_run (this=0x55c5dc723690) at /usr/include/c++/11/bits/std_thread.h:211
#15 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#16 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#17 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 12 (Thread 0x7f80b971a640 (LWP 1526202) "publisher_membe"):
#0  __futex_abstimed_wait_common64 (private=0, cancel=true, abstime=0x0, op=393, expected=0, futex_word=0x55c5dc6271fc) at ./nptl/futex-internal.c:57
#1  __futex_abstimed_wait_common (cancel=true, private=0, abstime=0x0, clockid=0, expected=0, futex_word=0x55c5dc6271fc) at ./nptl/futex-internal.c:87
#2  __GI___futex_abstimed_wait_cancelable64 (futex_word=futex_word@entry=0x55c5dc6271fc, expected=expected@entry=0, clockid=clockid@entry=0, abstime=abstime@entry=0x0, private=private@entry=0) at ./nptl/futex-internal.c:139
#3  0x00007f80c4c22ac1 in __pthread_cond_wait_common (abstime=0x0, clockid=0, mutex=0x55c5dc627268, cond=0x55c5dc6271d0) at ./nptl/pthread_cond_wait.c:503
#4  ___pthread_cond_wait (cond=0x55c5dc6271d0, mutex=0x55c5dc627268) at ./nptl/pthread_cond_wait.c:627
#5  0x00007f80c2e663f9 in eprosima::fastdds::rtps::FlowControllerAsyncPublishMode::wait (this=0x55c5dc6271b8, lock=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/rtps/flowcontrol/FlowControllerImpl.hpp:223
#6  0x00007f80c2e7e502 in eprosima::fastdds::rtps::FlowControllerImpl<eprosima::fastdds::rtps::FlowControllerSyncPublishMode, eprosima::fastdds::rtps::FlowControllerFifoSchedule>::run (this=0x55c5dc626ad0) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/rtps/flowcontrol/FlowControllerImpl.hpp:1291
#7  0x00007f80c2e81bb1 in std::__invoke_impl<void, void (eprosima::fastdds::rtps::FlowControllerImpl<eprosima::fastdds::rtps::FlowControllerSyncPublishMode, eprosima::fastdds::rtps::FlowControllerFifoSchedule>::*)(), eprosima::fastdds::rtps::FlowControllerImpl<eprosima::fastdds::rtps::FlowControllerSyncPublishMode, eprosima::fastdds::rtps::FlowControllerFifoSchedule>*> (__f=@0x55c5dc673e50: (void (eprosima::fastdds::rtps::FlowControllerImpl<eprosima::fastdds::rtps::FlowControllerSyncPublishMode, eprosima::fastdds::rtps::FlowControllerFifoSchedule>::*)(eprosima::fastdds::rtps::FlowControllerImpl<eprosima::fastdds::rtps::FlowControllerSyncPublishMode, eprosima::fastdds::rtps::FlowControllerFifoSchedule> * const)) 0x7f80c2e7e432 <eprosima::fastdds::rtps::FlowControllerImpl<eprosima::fastdds::rtps::FlowControllerSyncPublishMode, eprosima::fastdds::rtps::FlowControllerFifoSchedule>::run()>, __t=@0x55c5dc673e48: 0x55c5dc626ad0) at /usr/include/c++/11/bits/invoke.h:74
#8  0x00007f80c2e81603 in std::__invoke<void (eprosima::fastdds::rtps::FlowControllerImpl<eprosima::fastdds::rtps::FlowControllerSyncPublishMode, eprosima::fastdds::rtps::FlowControllerFifoSchedule>::*)(), eprosima::fastdds::rtps::FlowControllerImpl<eprosima::fastdds::rtps::FlowControllerSyncPublishMode, eprosima::fastdds::rtps::FlowControllerFifoSchedule>*> (__fn=@0x55c5dc673e50: (void (eprosima::fastdds::rtps::FlowControllerImpl<eprosima::fastdds::rtps::FlowControllerSyncPublishMode, eprosima::fastdds::rtps::FlowControllerFifoSchedule>::*)(eprosima::fastdds::rtps::FlowControllerImpl<eprosima::fastdds::rtps::FlowControllerSyncPublishMode, eprosima::fastdds::rtps::FlowControllerFifoSchedule> * const)) 0x7f80c2e7e432 <eprosima::fastdds::rtps::FlowControllerImpl<eprosima::fastdds::rtps::FlowControllerSyncPublishMode, eprosima::fastdds::rtps::FlowControllerFifoSchedule>::run()>) at /usr/include/c++/11/bits/invoke.h:96
#9  0x00007f80c2e812f3 in std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::FlowControllerImpl<eprosima::fastdds::rtps::FlowControllerSyncPublishMode, eprosima::fastdds::rtps::FlowControllerFifoSchedule>::*)(), eprosima::fastdds::rtps::FlowControllerImpl<eprosima::fastdds::rtps::FlowControllerSyncPublishMode, eprosima::fastdds::rtps::FlowControllerFifoSchedule>*> >::_M_invoke<0ul, 1ul> (this=0x55c5dc673e48) at /usr/include/c++/11/bits/std_thread.h:253
#10 0x00007f80c2e811a8 in std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::FlowControllerImpl<eprosima::fastdds::rtps::FlowControllerSyncPublishMode, eprosima::fastdds::rtps::FlowControllerFifoSchedule>::*)(), eprosima::fastdds::rtps::FlowControllerImpl<eprosima::fastdds::rtps::FlowControllerSyncPublishMode, eprosima::fastdds::rtps::FlowControllerFifoSchedule>*> >::operator() (this=0x55c5dc673e48) at /usr/include/c++/11/bits/std_thread.h:260
#11 0x00007f80c2e81068 in std::thread::_State_impl<std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::FlowControllerImpl<eprosima::fastdds::rtps::FlowControllerSyncPublishMode, eprosima::fastdds::rtps::FlowControllerFifoSchedule>::*)(), eprosima::fastdds::rtps::FlowControllerImpl<eprosima::fastdds::rtps::FlowControllerSyncPublishMode, eprosima::fastdds::rtps::FlowControllerFifoSchedule>*> > >::_M_run (this=0x55c5dc673e40) at /usr/include/c++/11/bits/std_thread.h:211
#12 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#13 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#14 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 11 (Thread 0x7f80b9ffb640 (LWP 1526201) "publisher_membe"):
#0  __futex_abstimed_wait_common64 (private=<optimized out>, cancel=true, abstime=0x7f80b9ff9560, op=265, expected=0, futex_word=0x7f80c1e78110) at ./nptl/futex-internal.c:57
#1  __futex_abstimed_wait_common (cancel=true, private=<optimized out>, abstime=0x7f80b9ff9560, clockid=0, expected=0, futex_word=0x7f80c1e78110) at ./nptl/futex-internal.c:87
#2  __GI___futex_abstimed_wait_cancelable64 (futex_word=futex_word@entry=0x7f80c1e78110, expected=expected@entry=0, clockid=clockid@entry=0, abstime=abstime@entry=0x7f80b9ff9560, private=<optimized out>) at ./nptl/futex-internal.c:139
#3  0x00007f80c4c2ba30 in do_futex_wait (sem=sem@entry=0x7f80c1e78110, abstime=abstime@entry=0x7f80b9ff9560, clockid=0) at ./nptl/sem_waitcommon.c:111
#4  0x00007f80c4c2bad3 in __new_sem_wait_slow64 (sem=0x7f80c1e78110, abstime=0x7f80b9ff9560, clockid=0) at ./nptl/sem_waitcommon.c:183
#5  0x00007f80c2a9ff7b in boost::interprocess::ipcdetail::semaphore_timed_wait (handle=0x7f80c1e78110, abs_time=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/sync/posix/semaphore_wrapper.hpp:226
#6  0x00007f80c2aa0063 in boost::interprocess::ipcdetail::posix_semaphore::timed_wait (this=0x7f80c1e78110, abs_time=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/sync/posix/semaphore.hpp:55
#7  0x00007f80c2aa008d in boost::interprocess::interprocess_semaphore::timed_wait (this=0x7f80c1e78110, abs_time=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/sync/interprocess_semaphore.hpp:139
#8  0x00007f80c2f83342 in eprosima::fastdds::rtps::RobustInterprocessCondition::do_timed_wait (this=0x7f80c1e73138, abs_time=..., mut=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/utils/shared_memory/RobustInterprocessCondition.hpp:398
#9  0x00007f80c2f9030c in eprosima::fastdds::rtps::RobustInterprocessCondition::timed_wait<std::unique_lock<boost::interprocess::interprocess_mutex>, eprosima::fastdds::rtps::SharedMemGlobal::Port::wait_pop(eprosima::fastdds::rtps::MultiProducerConsumerRingBuffer<eprosima::fastdds::rtps::SharedMemGlobal::BufferDescriptor>::Listener&, std::atomic<bool> const&, unsigned int)::{lambda()#1}>(std::unique_lock<boost::interprocess::interprocess_mutex>&, boost::posix_time::ptime const&, eprosima::fastdds::rtps::SharedMemGlobal::Port::wait_pop(eprosima::fastdds::rtps::MultiProducerConsumerRingBuffer<eprosima::fastdds::rtps::SharedMemGlobal::BufferDescriptor>::Listener&, std::atomic<bool> const&, unsigned int)::{lambda()#1}) (this=0x7f80c1e73138, lock=..., abs_time=..., pred=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/utils/shared_memory/RobustInterprocessCondition.hpp:148
#10 0x00007f80c2f869e0 in eprosima::fastdds::rtps::SharedMemGlobal::Port::wait_pop (this=0x55c5dc5efaf0, listener=..., is_listener_closed=std::atomic<bool> = { false }, listener_index=0) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/rtps/transport/shared_mem/SharedMemGlobal.hpp:576
#11 0x00007f80c2f8b013 in eprosima::fastdds::rtps::SharedMemManager::Listener::pop (this=0x55c5dc5ef940) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/rtps/transport/shared_mem/SharedMemManager.hpp:696
#12 0x00007f80c2f8ea69 in eprosima::fastdds::rtps::SharedMemChannelResource::Receive (this=0x55c5dc5efbe0, remote_locator=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/rtps/transport/shared_mem/SharedMemChannelResource.hpp:182
#13 0x00007f80c2f8e5c2 in eprosima::fastdds::rtps::SharedMemChannelResource::perform_listen_operation (this=0x55c5dc5efbe0, input_locator=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/rtps/transport/shared_mem/SharedMemChannelResource.hpp:133
#14 0x00007f80c2fa9baf in std::__invoke_impl<void, void (eprosima::fastdds::rtps::SharedMemChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::SharedMemChannelResource*, eprosima::fastrtps::rtps::Locator_t> (__f=@0x55c5dc5efc98: (void (eprosima::fastdds::rtps::SharedMemChannelResource::*)(eprosima::fastdds::rtps::SharedMemChannelResource * const, eprosima::fastrtps::rtps::Locator_t)) 0x7f80c2f8e538 <eprosima::fastdds::rtps::SharedMemChannelResource::perform_listen_operation(eprosima::fastrtps::rtps::Locator_t)>, __t=@0x55c5dc5efc90: 0x55c5dc5efbe0) at /usr/include/c++/11/bits/invoke.h:74
#15 0x00007f80c2fa9718 in std::__invoke<void (eprosima::fastdds::rtps::SharedMemChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::SharedMemChannelResource*, eprosima::fastrtps::rtps::Locator_t> (__fn=@0x55c5dc5efc98: (void (eprosima::fastdds::rtps::SharedMemChannelResource::*)(eprosima::fastdds::rtps::SharedMemChannelResource * const, eprosima::fastrtps::rtps::Locator_t)) 0x7f80c2f8e538 <eprosima::fastdds::rtps::SharedMemChannelResource::perform_listen_operation(eprosima::fastrtps::rtps::Locator_t)>) at /usr/include/c++/11/bits/invoke.h:96
#16 0x00007f80c2fa94e9 in std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::SharedMemChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::SharedMemChannelResource*, eprosima::fastrtps::rtps::Locator_t> >::_M_invoke<0ul, 1ul, 2ul> (this=0x55c5dc5efc78) at /usr/include/c++/11/bits/std_thread.h:253
#17 0x00007f80c2fa8f88 in std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::SharedMemChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::SharedMemChannelResource*, eprosima::fastrtps::rtps::Locator_t> >::operator() (this=0x55c5dc5efc78) at /usr/include/c++/11/bits/std_thread.h:260
#18 0x00007f80c2fa884e in std::thread::_State_impl<std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::SharedMemChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::SharedMemChannelResource*, eprosima::fastrtps::rtps::Locator_t> > >::_M_run (this=0x55c5dc5efc70) at /usr/include/c++/11/bits/std_thread.h:211
#19 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#20 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#21 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 10 (Thread 0x7f80ba7fc640 (LWP 1526200) "publisher_membe"):
#0  0x00007f80c4cb6934 in __libc_recvfrom (fd=37, buf=0x55c5dc6141d0, len=65500, flags=0, addr=..., addrlen=0x7f80ba7fa75c) at ../sysdeps/unix/sysv/linux/recvfrom.c:27
#1  0x00007f80c2c3ce9e in asio::detail::socket_ops::call_recvfrom<unsigned int> (s=37, data=0x55c5dc6141d0, size=65500, flags=0, addr=0x7f80ba7faa10, addrlen=0x7f80ba7fa8c0) at /usr/include/asio/detail/impl/socket_ops.ipp:1053
#2  0x00007f80c2c3bed3 in asio::detail::socket_ops::recvfrom1 (s=37, data=0x55c5dc6141d0, size=65500, flags=0, addr=0x7f80ba7faa10, addrlen=0x7f80ba7fa8c0, ec=std::error_code = {std::_V2::error_category: 0}) at /usr/include/asio/detail/impl/socket_ops.ipp:1087
#3  0x00007f80c2c3bf85 in asio::detail::socket_ops::sync_recvfrom1 (s=37, state=32 ' ', data=0x55c5dc6141d0, size=65500, flags=0, addr=0x7f80ba7faa10, addrlen=0x7f80ba7fa8c0, ec=std::error_code = {std::_V2::error_category: 0}) at /usr/include/asio/detail/impl/socket_ops.ipp:1141
#4  0x00007f80c2c3d66e in asio::detail::reactive_socket_service<asio::ip::udp>::receive_from<asio::mutable_buffers_1> (this=0x55c5dc5e6200, impl=..., buffers=..., sender_endpoint=..., flags=0, ec=std::error_code = {std::_V2::error_category: 0}) at /usr/include/asio/detail/reactive_socket_service.hpp:315
#5  0x00007f80c2c3d197 in asio::basic_datagram_socket<asio::ip::udp, asio::execution::any_executor<asio::execution::context_as_t<asio::execution_context&>, asio::execution::detail::blocking::never_t<0>, asio::execution::prefer_only<asio::execution::detail::blocking::possibly_t<0> >, asio::execution::prefer_only<asio::execution::detail::outstanding_work::tracked_t<0> >, asio::execution::prefer_only<asio::execution::detail::outstanding_work::untracked_t<0> >, asio::execution::prefer_only<asio::execution::detail::relationship::fork_t<0> >, asio::execution::prefer_only<asio::execution::detail::relationship::continuation_t<0> > > >::receive_from<asio::mutable_buffers_1> (this=0x55c5dc5ef2b0, buffers=..., sender_endpoint=...) at /usr/include/asio/basic_datagram_socket.hpp:911
#6  0x00007f80c2c3a323 in eprosima::fastdds::rtps::UDPChannelResource::Receive (this=0x55c5dc5ef270, receive_buffer=0x55c5dc6141d0 "", receive_buffer_capacity=65500, receive_buffer_size=@0x55c5dc5ef28c: 0, remote_locator=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/rtps/transport/UDPChannelResource.cpp:91
#7  0x00007f80c2c3a0b5 in eprosima::fastdds::rtps::UDPChannelResource::perform_listen_operation (this=0x55c5dc5ef270, input_locator=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/rtps/transport/UDPChannelResource.cpp:62
#8  0x00007f80c2c3de5a in std::__invoke_impl<void, void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t> (__f=@0x55c5dc5eec68: (void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastdds::rtps::UDPChannelResource * const, eprosima::fastrtps::rtps::Locator_t)) 0x7f80c2c3a026 <eprosima::fastdds::rtps::UDPChannelResource::perform_listen_operation(eprosima::fastrtps::rtps::Locator_t)>, __t=@0x55c5dc5eec60: 0x55c5dc5ef270) at /usr/include/c++/11/bits/invoke.h:74
#9  0x00007f80c2c3dd50 in std::__invoke<void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t> (__fn=@0x55c5dc5eec68: (void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastdds::rtps::UDPChannelResource * const, eprosima::fastrtps::rtps::Locator_t)) 0x7f80c2c3a026 <eprosima::fastdds::rtps::UDPChannelResource::perform_listen_operation(eprosima::fastrtps::rtps::Locator_t)>) at /usr/include/c++/11/bits/invoke.h:96
#10 0x00007f80c2c3dc6f in std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t> >::_M_invoke<0ul, 1ul, 2ul> (this=0x55c5dc5eec48) at /usr/include/c++/11/bits/std_thread.h:253
#11 0x00007f80c2c3dc08 in std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t> >::operator() (this=0x55c5dc5eec48) at /usr/include/c++/11/bits/std_thread.h:260
#12 0x00007f80c2c3dbe8 in std::thread::_State_impl<std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t> > >::_M_run (this=0x55c5dc5eec40) at /usr/include/c++/11/bits/std_thread.h:211
#13 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#14 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#15 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 9 (Thread 0x7f80baffd640 (LWP 1526199) "publisher_membe"):
#0  __futex_abstimed_wait_common64 (private=<optimized out>, cancel=true, abstime=0x7f80baffb560, op=265, expected=0, futex_word=0x7f80c1e85110) at ./nptl/futex-internal.c:57
#1  __futex_abstimed_wait_common (cancel=true, private=<optimized out>, abstime=0x7f80baffb560, clockid=0, expected=0, futex_word=0x7f80c1e85110) at ./nptl/futex-internal.c:87
#2  __GI___futex_abstimed_wait_cancelable64 (futex_word=futex_word@entry=0x7f80c1e85110, expected=expected@entry=0, clockid=clockid@entry=0, abstime=abstime@entry=0x7f80baffb560, private=<optimized out>) at ./nptl/futex-internal.c:139
#3  0x00007f80c4c2ba30 in do_futex_wait (sem=sem@entry=0x7f80c1e85110, abstime=abstime@entry=0x7f80baffb560, clockid=0) at ./nptl/sem_waitcommon.c:111
#4  0x00007f80c4c2bad3 in __new_sem_wait_slow64 (sem=0x7f80c1e85110, abstime=0x7f80baffb560, clockid=0) at ./nptl/sem_waitcommon.c:183
#5  0x00007f80c2a9ff7b in boost::interprocess::ipcdetail::semaphore_timed_wait (handle=0x7f80c1e85110, abs_time=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/sync/posix/semaphore_wrapper.hpp:226
#6  0x00007f80c2aa0063 in boost::interprocess::ipcdetail::posix_semaphore::timed_wait (this=0x7f80c1e85110, abs_time=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/sync/posix/semaphore.hpp:55
#7  0x00007f80c2aa008d in boost::interprocess::interprocess_semaphore::timed_wait (this=0x7f80c1e85110, abs_time=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/sync/interprocess_semaphore.hpp:139
#8  0x00007f80c2f83342 in eprosima::fastdds::rtps::RobustInterprocessCondition::do_timed_wait (this=0x7f80c1e80138, abs_time=..., mut=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/utils/shared_memory/RobustInterprocessCondition.hpp:398
#9  0x00007f80c2f9030c in eprosima::fastdds::rtps::RobustInterprocessCondition::timed_wait<std::unique_lock<boost::interprocess::interprocess_mutex>, eprosima::fastdds::rtps::SharedMemGlobal::Port::wait_pop(eprosima::fastdds::rtps::MultiProducerConsumerRingBuffer<eprosima::fastdds::rtps::SharedMemGlobal::BufferDescriptor>::Listener&, std::atomic<bool> const&, unsigned int)::{lambda()#1}>(std::unique_lock<boost::interprocess::interprocess_mutex>&, boost::posix_time::ptime const&, eprosima::fastdds::rtps::SharedMemGlobal::Port::wait_pop(eprosima::fastdds::rtps::MultiProducerConsumerRingBuffer<eprosima::fastdds::rtps::SharedMemGlobal::BufferDescriptor>::Listener&, std::atomic<bool> const&, unsigned int)::{lambda()#1}) (this=0x7f80c1e80138, lock=..., abs_time=..., pred=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/utils/shared_memory/RobustInterprocessCondition.hpp:148
#10 0x00007f80c2f869e0 in eprosima::fastdds::rtps::SharedMemGlobal::Port::wait_pop (this=0x55c5dc5eeb10, listener=..., is_listener_closed=std::atomic<bool> = { false }, listener_index=0) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/rtps/transport/shared_mem/SharedMemGlobal.hpp:576
#11 0x00007f80c2f8b013 in eprosima::fastdds::rtps::SharedMemManager::Listener::pop (this=0x55c5dc5ee8e0) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/rtps/transport/shared_mem/SharedMemManager.hpp:696
#12 0x00007f80c2f8ea69 in eprosima::fastdds::rtps::SharedMemChannelResource::Receive (this=0x55c5dc5eec80, remote_locator=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/rtps/transport/shared_mem/SharedMemChannelResource.hpp:182
#13 0x00007f80c2f8e5c2 in eprosima::fastdds::rtps::SharedMemChannelResource::perform_listen_operation (this=0x55c5dc5eec80, input_locator=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/rtps/transport/shared_mem/SharedMemChannelResource.hpp:133
#14 0x00007f80c2fa9baf in std::__invoke_impl<void, void (eprosima::fastdds::rtps::SharedMemChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::SharedMemChannelResource*, eprosima::fastrtps::rtps::Locator_t> (__f=@0x55c5dc5eed38: (void (eprosima::fastdds::rtps::SharedMemChannelResource::*)(eprosima::fastdds::rtps::SharedMemChannelResource * const, eprosima::fastrtps::rtps::Locator_t)) 0x7f80c2f8e538 <eprosima::fastdds::rtps::SharedMemChannelResource::perform_listen_operation(eprosima::fastrtps::rtps::Locator_t)>, __t=@0x55c5dc5eed30: 0x55c5dc5eec80) at /usr/include/c++/11/bits/invoke.h:74
#15 0x00007f80c2fa9718 in std::__invoke<void (eprosima::fastdds::rtps::SharedMemChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::SharedMemChannelResource*, eprosima::fastrtps::rtps::Locator_t> (__fn=@0x55c5dc5eed38: (void (eprosima::fastdds::rtps::SharedMemChannelResource::*)(eprosima::fastdds::rtps::SharedMemChannelResource * const, eprosima::fastrtps::rtps::Locator_t)) 0x7f80c2f8e538 <eprosima::fastdds::rtps::SharedMemChannelResource::perform_listen_operation(eprosima::fastrtps::rtps::Locator_t)>) at /usr/include/c++/11/bits/invoke.h:96
#16 0x00007f80c2fa94e9 in std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::SharedMemChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::SharedMemChannelResource*, eprosima::fastrtps::rtps::Locator_t> >::_M_invoke<0ul, 1ul, 2ul> (this=0x55c5dc5eed18) at /usr/include/c++/11/bits/std_thread.h:253
#17 0x00007f80c2fa8f88 in std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::SharedMemChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::SharedMemChannelResource*, eprosima::fastrtps::rtps::Locator_t> >::operator() (this=0x55c5dc5eed18) at /usr/include/c++/11/bits/std_thread.h:260
#18 0x00007f80c2fa884e in std::thread::_State_impl<std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::SharedMemChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::SharedMemChannelResource*, eprosima::fastrtps::rtps::Locator_t> > >::_M_run (this=0x55c5dc5eed10) at /usr/include/c++/11/bits/std_thread.h:211
#19 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#20 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#21 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 8 (Thread 0x7f80bb7fe640 (LWP 1526198) "publisher_membe"):
#0  0x00007f80c4cb6934 in __libc_recvfrom (fd=35, buf=0x55c5dc6018d0, len=65500, flags=0, addr=..., addrlen=0x7f80bb7fc75c) at ../sysdeps/unix/sysv/linux/recvfrom.c:27
#1  0x00007f80c2c3ce9e in asio::detail::socket_ops::call_recvfrom<unsigned int> (s=35, data=0x55c5dc6018d0, size=65500, flags=0, addr=0x7f80bb7fca10, addrlen=0x7f80bb7fc8c0) at /usr/include/asio/detail/impl/socket_ops.ipp:1053
#2  0x00007f80c2c3bed3 in asio::detail::socket_ops::recvfrom1 (s=35, data=0x55c5dc6018d0, size=65500, flags=0, addr=0x7f80bb7fca10, addrlen=0x7f80bb7fc8c0, ec=std::error_code = {std::_V2::error_category: 0}) at /usr/include/asio/detail/impl/socket_ops.ipp:1087
#3  0x00007f80c2c3bf85 in asio::detail::socket_ops::sync_recvfrom1 (s=35, state=32 ' ', data=0x55c5dc6018d0, size=65500, flags=0, addr=0x7f80bb7fca10, addrlen=0x7f80bb7fc8c0, ec=std::error_code = {std::_V2::error_category: 0}) at /usr/include/asio/detail/impl/socket_ops.ipp:1141
#4  0x00007f80c2c3d66e in asio::detail::reactive_socket_service<asio::ip::udp>::receive_from<asio::mutable_buffers_1> (this=0x55c5dc5e6200, impl=..., buffers=..., sender_endpoint=..., flags=0, ec=std::error_code = {std::_V2::error_category: 0}) at /usr/include/asio/detail/reactive_socket_service.hpp:315
#5  0x00007f80c2c3d197 in asio::basic_datagram_socket<asio::ip::udp, asio::execution::any_executor<asio::execution::context_as_t<asio::execution_context&>, asio::execution::detail::blocking::never_t<0>, asio::execution::prefer_only<asio::execution::detail::blocking::possibly_t<0> >, asio::execution::prefer_only<asio::execution::detail::outstanding_work::tracked_t<0> >, asio::execution::prefer_only<asio::execution::detail::outstanding_work::untracked_t<0> >, asio::execution::prefer_only<asio::execution::detail::relationship::fork_t<0> >, asio::execution::prefer_only<asio::execution::detail::relationship::continuation_t<0> > > >::receive_from<asio::mutable_buffers_1> (this=0x55c5dc601190, buffers=..., sender_endpoint=...) at /usr/include/asio/basic_datagram_socket.hpp:911
#6  0x00007f80c2c3a323 in eprosima::fastdds::rtps::UDPChannelResource::Receive (this=0x55c5dc601150, receive_buffer=0x55c5dc6018d0 "", receive_buffer_capacity=65500, receive_buffer_size=@0x55c5dc60116c: 0, remote_locator=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/rtps/transport/UDPChannelResource.cpp:91
#7  0x00007f80c2c3a0b5 in eprosima::fastdds::rtps::UDPChannelResource::perform_listen_operation (this=0x55c5dc601150, input_locator=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/rtps/transport/UDPChannelResource.cpp:62
#8  0x00007f80c2c3de5a in std::__invoke_impl<void, void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t> (__f=@0x55c5dc5f10d8: (void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastdds::rtps::UDPChannelResource * const, eprosima::fastrtps::rtps::Locator_t)) 0x7f80c2c3a026 <eprosima::fastdds::rtps::UDPChannelResource::perform_listen_operation(eprosima::fastrtps::rtps::Locator_t)>, __t=@0x55c5dc5f10d0: 0x55c5dc601150) at /usr/include/c++/11/bits/invoke.h:74
#9  0x00007f80c2c3dd50 in std::__invoke<void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t> (__fn=@0x55c5dc5f10d8: (void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastdds::rtps::UDPChannelResource * const, eprosima::fastrtps::rtps::Locator_t)) 0x7f80c2c3a026 <eprosima::fastdds::rtps::UDPChannelResource::perform_listen_operation(eprosima::fastrtps::rtps::Locator_t)>) at /usr/include/c++/11/bits/invoke.h:96
#10 0x00007f80c2c3dc6f in std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t> >::_M_invoke<0ul, 1ul, 2ul> (this=0x55c5dc5f10b8) at /usr/include/c++/11/bits/std_thread.h:253
#11 0x00007f80c2c3dc08 in std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t> >::operator() (this=0x55c5dc5f10b8) at /usr/include/c++/11/bits/std_thread.h:260
#12 0x00007f80c2c3dbe8 in std::thread::_State_impl<std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t> > >::_M_run (this=0x55c5dc5f10b0) at /usr/include/c++/11/bits/std_thread.h:211
#13 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#14 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#15 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 7 (Thread 0x7f80bbfff640 (LWP 1526197) "publisher_membe"):
#0  0x00007f80c4cb6934 in __libc_recvfrom (fd=34, buf=0x55c5dc5f1160, len=65500, flags=0, addr=..., addrlen=0x7f80bbffd75c) at ../sysdeps/unix/sysv/linux/recvfrom.c:27
#1  0x00007f80c2c3ce9e in asio::detail::socket_ops::call_recvfrom<unsigned int> (s=34, data=0x55c5dc5f1160, size=65500, flags=0, addr=0x7f80bbffda10, addrlen=0x7f80bbffd8c0) at /usr/include/asio/detail/impl/socket_ops.ipp:1053
#2  0x00007f80c2c3bed3 in asio::detail::socket_ops::recvfrom1 (s=34, data=0x55c5dc5f1160, size=65500, flags=0, addr=0x7f80bbffda10, addrlen=0x7f80bbffd8c0, ec=std::error_code = {std::_V2::error_category: 0}) at /usr/include/asio/detail/impl/socket_ops.ipp:1087
#3  0x00007f80c2c3bf85 in asio::detail::socket_ops::sync_recvfrom1 (s=34, state=32 ' ', data=0x55c5dc5f1160, size=65500, flags=0, addr=0x7f80bbffda10, addrlen=0x7f80bbffd8c0, ec=std::error_code = {std::_V2::error_category: 0}) at /usr/include/asio/detail/impl/socket_ops.ipp:1141
#4  0x00007f80c2c3d66e in asio::detail::reactive_socket_service<asio::ip::udp>::receive_from<asio::mutable_buffers_1> (this=0x55c5dc5e6200, impl=..., buffers=..., sender_endpoint=..., flags=0, ec=std::error_code = {std::_V2::error_category: 0}) at /usr/include/asio/detail/reactive_socket_service.hpp:315
#5  0x00007f80c2c3d197 in asio::basic_datagram_socket<asio::ip::udp, asio::execution::any_executor<asio::execution::context_as_t<asio::execution_context&>, asio::execution::detail::blocking::never_t<0>, asio::execution::prefer_only<asio::execution::detail::blocking::possibly_t<0> >, asio::execution::prefer_only<asio::execution::detail::outstanding_work::tracked_t<0> >, asio::execution::prefer_only<asio::execution::detail::outstanding_work::untracked_t<0> >, asio::execution::prefer_only<asio::execution::detail::relationship::fork_t<0> >, asio::execution::prefer_only<asio::execution::detail::relationship::continuation_t<0> > > >::receive_from<asio::mutable_buffers_1> (this=0x55c5dc5edec0, buffers=..., sender_endpoint=...) at /usr/include/asio/basic_datagram_socket.hpp:911
#6  0x00007f80c2c3a323 in eprosima::fastdds::rtps::UDPChannelResource::Receive (this=0x55c5dc5ede80, receive_buffer=0x55c5dc5f1160 "RTPS\002\003\001\017\001\017x\"\257I\253@\001", receive_buffer_capacity=65500, receive_buffer_size=@0x55c5dc5ede9c: 364, remote_locator=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/rtps/transport/UDPChannelResource.cpp:91
#7  0x00007f80c2c3a0b5 in eprosima::fastdds::rtps::UDPChannelResource::perform_listen_operation (this=0x55c5dc5ede80, input_locator=...) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/rtps/transport/UDPChannelResource.cpp:62
#8  0x00007f80c2c3de5a in std::__invoke_impl<void, void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t> (__f=@0x55c5dc5c0788: (void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastdds::rtps::UDPChannelResource * const, eprosima::fastrtps::rtps::Locator_t)) 0x7f80c2c3a026 <eprosima::fastdds::rtps::UDPChannelResource::perform_listen_operation(eprosima::fastrtps::rtps::Locator_t)>, __t=@0x55c5dc5c0780: 0x55c5dc5ede80) at /usr/include/c++/11/bits/invoke.h:74
#9  0x00007f80c2c3dd50 in std::__invoke<void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t> (__fn=@0x55c5dc5c0788: (void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastdds::rtps::UDPChannelResource * const, eprosima::fastrtps::rtps::Locator_t)) 0x7f80c2c3a026 <eprosima::fastdds::rtps::UDPChannelResource::perform_listen_operation(eprosima::fastrtps::rtps::Locator_t)>) at /usr/include/c++/11/bits/invoke.h:96
#10 0x00007f80c2c3dc6f in std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t> >::_M_invoke<0ul, 1ul, 2ul> (this=0x55c5dc5c0768) at /usr/include/c++/11/bits/std_thread.h:253
#11 0x00007f80c2c3dc08 in std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t> >::operator() (this=0x55c5dc5c0768) at /usr/include/c++/11/bits/std_thread.h:260
#12 0x00007f80c2c3dbe8 in std::thread::_State_impl<std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::UDPChannelResource::*)(eprosima::fastrtps::rtps::Locator_t), eprosima::fastdds::rtps::UDPChannelResource*, eprosima::fastrtps::rtps::Locator_t> > >::_M_run (this=0x55c5dc5c0760) at /usr/include/c++/11/bits/std_thread.h:211
#13 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#14 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#15 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 6 (Thread 0x7f80c08cb640 (LWP 1526196) "publisher_membe"):
#0  __futex_abstimed_wait_common64 (private=-597153192, cancel=true, abstime=0x7f80c08c9cd0, op=137, expected=0, futex_word=0x55c5dc5e914c) at ./nptl/futex-internal.c:57
#1  __futex_abstimed_wait_common (cancel=true, private=-597153192, abstime=0x7f80c08c9cd0, clockid=0, expected=0, futex_word=0x55c5dc5e914c) at ./nptl/futex-internal.c:87
#2  __GI___futex_abstimed_wait_cancelable64 (futex_word=futex_word@entry=0x55c5dc5e914c, expected=expected@entry=0, clockid=clockid@entry=1, abstime=abstime@entry=0x7f80c08c9cd0, private=private@entry=0) at ./nptl/futex-internal.c:139
#3  0x00007f80c4c2335d in __pthread_cond_wait_common (abstime=0x7f80c08c9cd0, clockid=1, mutex=0x55c5dc5c0530, cond=0x55c5dc5e9120) at ./nptl/pthread_cond_wait.c:503
#4  ___pthread_cond_clockwait64 (abstime=0x7f80c08c9cd0, clockid=1, mutex=0x55c5dc5c0530, cond=0x55c5dc5e9120) at ./nptl/pthread_cond_wait.c:691
#5  ___pthread_cond_clockwait64 (cond=0x55c5dc5e9120, mutex=0x55c5dc5c0530, clockid=1, abstime=0x7f80c08c9cd0) at ./nptl/pthread_cond_wait.c:679
#6  0x00007f80c29cd72d in std::__condvar::wait_until (this=0x55c5dc5e9120, __m=..., __clock=1, __abs_time=...) at /usr/include/c++/11/bits/std_mutex.h:169
#7  0x00007f80c29d0838 in std::condition_variable::__wait_until_impl<std::chrono::duration<long, std::ratio<1l, 1000000000l> > > (this=0x55c5dc5e9120, __lock=..., __atime=...) at /usr/include/c++/11/condition_variable:201
#8  0x00007f80c29cf85f in std::condition_variable::wait_until<std::chrono::duration<long, std::ratio<1l, 1000000000l> > > (this=0x55c5dc5e9120, __lock=..., __atime=...) at /usr/include/c++/11/condition_variable:111
#9  0x00007f80c29ce5d3 in std::_V2::condition_variable_any::wait_until<std::unique_lock<std::timed_mutex>, std::chrono::_V2::steady_clock, std::chrono::duration<long, std::ratio<1l, 1000000000l> > > (this=0x55c5dc5e9120, __lock=..., __atime=...) at /usr/include/c++/11/condition_variable:336
#10 0x00007f80c29ccbdc in eprosima::fastrtps::rtps::ResourceEvent::event_service (this=0x55c5dc5e90a8) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/rtps/resources/ResourceEvent.cpp:204
#11 0x00007f80c29d2e19 in std::__invoke_impl<void, void (eprosima::fastrtps::rtps::ResourceEvent::*)(), eprosima::fastrtps::rtps::ResourceEvent*> (__f=@0x55c5dc5ebbf0: (void (eprosima::fastrtps::rtps::ResourceEvent::*)(eprosima::fastrtps::rtps::ResourceEvent * const)) 0x7f80c29cca4c <eprosima::fastrtps::rtps::ResourceEvent::event_service()>, __t=@0x55c5dc5ebbe8: 0x55c5dc5e90a8) at /usr/include/c++/11/bits/invoke.h:74
#12 0x00007f80c29d2d6b in std::__invoke<void (eprosima::fastrtps::rtps::ResourceEvent::*)(), eprosima::fastrtps::rtps::ResourceEvent*> (__fn=@0x55c5dc5ebbf0: (void (eprosima::fastrtps::rtps::ResourceEvent::*)(eprosima::fastrtps::rtps::ResourceEvent * const)) 0x7f80c29cca4c <eprosima::fastrtps::rtps::ResourceEvent::event_service()>) at /usr/include/c++/11/bits/invoke.h:96
#13 0x00007f80c29d2ccb in std::thread::_Invoker<std::tuple<void (eprosima::fastrtps::rtps::ResourceEvent::*)(), eprosima::fastrtps::rtps::ResourceEvent*> >::_M_invoke<0ul, 1ul> (this=0x55c5dc5ebbe8) at /usr/include/c++/11/bits/std_thread.h:253
#14 0x00007f80c29d2c80 in std::thread::_Invoker<std::tuple<void (eprosima::fastrtps::rtps::ResourceEvent::*)(), eprosima::fastrtps::rtps::ResourceEvent*> >::operator() (this=0x55c5dc5ebbe8) at /usr/include/c++/11/bits/std_thread.h:260
#15 0x00007f80c29d2c60 in std::thread::_State_impl<std::thread::_Invoker<std::tuple<void (eprosima::fastrtps::rtps::ResourceEvent::*)(), eprosima::fastrtps::rtps::ResourceEvent*> > >::_M_run (this=0x55c5dc5ebbe0) at /usr/include/c++/11/bits/std_thread.h:211
#16 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#17 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#18 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 5 (Thread 0x7f80c1153640 (LWP 1526195) "publisher_membe"):
#0  __futex_abstimed_wait_common64 (private=-1029883984, cancel=true, abstime=0x7f80c1151cd0, op=137, expected=0, futex_word=0x55c5dc5e5930) at ./nptl/futex-internal.c:57
#1  __futex_abstimed_wait_common (cancel=true, private=-1029883984, abstime=0x7f80c1151cd0, clockid=0, expected=0, futex_word=0x55c5dc5e5930) at ./nptl/futex-internal.c:87
#2  __GI___futex_abstimed_wait_cancelable64 (futex_word=futex_word@entry=0x55c5dc5e5930, expected=expected@entry=0, clockid=clockid@entry=1, abstime=abstime@entry=0x7f80c1151cd0, private=private@entry=0) at ./nptl/futex-internal.c:139
#3  0x00007f80c4c2335d in __pthread_cond_wait_common (abstime=0x7f80c1151cd0, clockid=1, mutex=0x55c5dc5e5938, cond=0x55c5dc5e5908) at ./nptl/pthread_cond_wait.c:503
#4  ___pthread_cond_clockwait64 (abstime=0x7f80c1151cd0, clockid=1, mutex=0x55c5dc5e5938, cond=0x55c5dc5e5908) at ./nptl/pthread_cond_wait.c:691
#5  ___pthread_cond_clockwait64 (cond=0x55c5dc5e5908, mutex=0x55c5dc5e5938, clockid=1, abstime=0x7f80c1151cd0) at ./nptl/pthread_cond_wait.c:679
#6  0x00007f80c29cd72d in std::__condvar::wait_until (this=0x55c5dc5e5908, __m=..., __clock=1, __abs_time=...) at /usr/include/c++/11/bits/std_mutex.h:169
#7  0x00007f80c29d0838 in std::condition_variable::__wait_until_impl<std::chrono::duration<long, std::ratio<1l, 1000000000l> > > (this=0x55c5dc5e5908, __lock=..., __atime=...) at /usr/include/c++/11/condition_variable:201
#8  0x00007f80c29cf85f in std::condition_variable::wait_until<std::chrono::duration<long, std::ratio<1l, 1000000000l> > > (this=0x55c5dc5e5908, __lock=..., __atime=...) at /usr/include/c++/11/condition_variable:111
#9  0x00007f80c2f930e3 in std::condition_variable::wait_until<std::chrono::_V2::steady_clock, std::chrono::duration<long, std::ratio<1l, 1000000000l> >, eprosima::fastdds::rtps::SharedMemWatchdog::run()::{lambda()#1}>(std::unique_lock<std::mutex>&, std::chrono::time_point<std::chrono::_V2::steady_clock, std::chrono::duration<long, std::ratio<1l, 1000000000l> > > const&, eprosima::fastdds::rtps::SharedMemWatchdog::run()::{lambda()#1}) (this=0x55c5dc5e5908, __lock=..., __atime=..., __p=...) at /usr/include/c++/11/condition_variable:152
#10 0x00007f80c2f8f670 in std::condition_variable::wait_for<long, std::ratio<1l, 1000l>, eprosima::fastdds::rtps::SharedMemWatchdog::run()::{lambda()#1}>(std::unique_lock<std::mutex>&, std::chrono::duration<long, std::ratio<1l, 1000l> > const&, eprosima::fastdds::rtps::SharedMemWatchdog::run()::{lambda()#1}) (this=0x55c5dc5e5908, __lock=..., __rtime=..., __p=...) at /usr/include/c++/11/condition_variable:175
#11 0x00007f80c2f84f4e in eprosima::fastdds::rtps::SharedMemWatchdog::run (this=0x55c5dc5e58a0) at /home/chenlh/Projects/ROS2/ros2-humble/src/eProsima/Fast-DDS/src/cpp/utils/shared_memory/SharedMemWatchdog.hpp:129
#12 0x00007f80c2fa9c74 in std::__invoke_impl<void, void (eprosima::fastdds::rtps::SharedMemWatchdog::*)(), eprosima::fastdds::rtps::SharedMemWatchdog*> (__f=@0x55c5dc5e5bb0: (void (eprosima::fastdds::rtps::SharedMemWatchdog::*)(eprosima::fastdds::rtps::SharedMemWatchdog * const)) 0x7f80c2f84ee2 <eprosima::fastdds::rtps::SharedMemWatchdog::run()>, __t=@0x55c5dc5e5ba8: 0x55c5dc5e58a0) at /usr/include/c++/11/bits/invoke.h:74
#13 0x00007f80c2fa97bb in std::__invoke<void (eprosima::fastdds::rtps::SharedMemWatchdog::*)(), eprosima::fastdds::rtps::SharedMemWatchdog*> (__fn=@0x55c5dc5e5bb0: (void (eprosima::fastdds::rtps::SharedMemWatchdog::*)(eprosima::fastdds::rtps::SharedMemWatchdog * const)) 0x7f80c2f84ee2 <eprosima::fastdds::rtps::SharedMemWatchdog::run()>) at /usr/include/c++/11/bits/invoke.h:96
#14 0x00007f80c2fa953b in std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::SharedMemWatchdog::*)(), eprosima::fastdds::rtps::SharedMemWatchdog*> >::_M_invoke<0ul, 1ul> (this=0x55c5dc5e5ba8) at /usr/include/c++/11/bits/std_thread.h:253
#15 0x00007f80c2fa91ae in std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::SharedMemWatchdog::*)(), eprosima::fastdds::rtps::SharedMemWatchdog*> >::operator() (this=0x55c5dc5e5ba8) at /usr/include/c++/11/bits/std_thread.h:260
#16 0x00007f80c2fa8c1c in std::thread::_State_impl<std::thread::_Invoker<std::tuple<void (eprosima::fastdds::rtps::SharedMemWatchdog::*)(), eprosima::fastdds::rtps::SharedMemWatchdog*> > >::_M_run (this=0x55c5dc5e5ba0) at /usr/include/c++/11/bits/std_thread.h:211
#17 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#18 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#19 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 4 (Thread 0x7f80c1954640 (LWP 1526194) "publisher_membe"):
#0  __futex_abstimed_wait_common64 (private=<optimized out>, cancel=true, abstime=0x0, op=393, expected=0, futex_word=0x7f80c5e84368 <rclcpp::SignalHandler::get_global_signal_handler()::signal_handler+392>) at ./nptl/futex-internal.c:57
#1  __futex_abstimed_wait_common (cancel=true, private=<optimized out>, abstime=0x0, clockid=0, expected=0, futex_word=0x7f80c5e84368 <rclcpp::SignalHandler::get_global_signal_handler()::signal_handler+392>) at ./nptl/futex-internal.c:87
#2  __GI___futex_abstimed_wait_cancelable64 (futex_word=futex_word@entry=0x7f80c5e84368 <rclcpp::SignalHandler::get_global_signal_handler()::signal_handler+392>, expected=expected@entry=0, clockid=clockid@entry=0, abstime=abstime@entry=0x0, private=<optimized out>) at ./nptl/futex-internal.c:139
#3  0x00007f80c4c2bc5f in do_futex_wait (sem=sem@entry=0x7f80c5e84368 <rclcpp::SignalHandler::get_global_signal_handler()::signal_handler+392>, abstime=0x0, clockid=0) at ./nptl/sem_waitcommon.c:111
#4  0x00007f80c4c2bcf8 in __new_sem_wait_slow64 (sem=0x7f80c5e84368 <rclcpp::SignalHandler::get_global_signal_handler()::signal_handler+392>, abstime=0x0, clockid=0) at ./nptl/sem_waitcommon.c:183
#5  0x00007f80c5c30b73 in rclcpp::SignalHandler::wait_for_signal (this=0x7f80c5e841e0 <rclcpp::SignalHandler::get_global_signal_handler()::signal_handler>) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/signal_handler.cpp:359
#6  0x00007f80c5c30503 in rclcpp::SignalHandler::deferred_signal_handler (this=0x7f80c5e841e0 <rclcpp::SignalHandler::get_global_signal_handler()::signal_handler>) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/signal_handler.cpp:279
#7  0x00007f80c5c3147d in std::__invoke_impl<void, void (rclcpp::SignalHandler::*)(), rclcpp::SignalHandler*> (__f=@0x55c5dc5e2fb0: (void (rclcpp::SignalHandler::*)(rclcpp::SignalHandler * const)) 0x7f80c5c2fe6e <rclcpp::SignalHandler::deferred_signal_handler()>, __t=@0x55c5dc5e2fa8: 0x7f80c5e841e0 <rclcpp::SignalHandler::get_global_signal_handler()::signal_handler>) at /usr/include/c++/11/bits/invoke.h:74
#8  0x00007f80c5c313ff in std::__invoke<void (rclcpp::SignalHandler::*)(), rclcpp::SignalHandler*> (__fn=@0x55c5dc5e2fb0: (void (rclcpp::SignalHandler::*)(rclcpp::SignalHandler * const)) 0x7f80c5c2fe6e <rclcpp::SignalHandler::deferred_signal_handler()>) at /usr/include/c++/11/bits/invoke.h:96
#9  0x00007f80c5c3135f in std::thread::_Invoker<std::tuple<void (rclcpp::SignalHandler::*)(), rclcpp::SignalHandler*> >::_M_invoke<0ul, 1ul> (this=0x55c5dc5e2fa8) at /usr/include/c++/11/bits/std_thread.h:253
#10 0x00007f80c5c31314 in std::thread::_Invoker<std::tuple<void (rclcpp::SignalHandler::*)(), rclcpp::SignalHandler*> >::operator() (this=0x55c5dc5e2fa8) at /usr/include/c++/11/bits/std_thread.h:260
#11 0x00007f80c5c312f4 in std::thread::_State_impl<std::thread::_Invoker<std::tuple<void (rclcpp::SignalHandler::*)(), rclcpp::SignalHandler*> > >::_M_run (this=0x55c5dc5e2fa0) at /usr/include/c++/11/bits/std_thread.h:211
#12 0x00007f80c4eb32b3 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#13 0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#14 0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 3 (Thread 0x7f80c4025640 (LWP 1526193) "publisher_m-ust"):
#0  syscall () at ../sysdeps/unix/sysv/linux/x86_64/syscall.S:38
#1  0x00007f80c4968136 in ?? () from /lib/x86_64-linux-gnu/liblttng-ust.so.1
#2  0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#3  0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 2 (Thread 0x7f80c4826640 (LWP 1526192) "publisher_m-ust"):
#0  __recvmsg_syscall (flags=0, msg=0x7f80c48246b0, fd=3) at ../sysdeps/unix/sysv/linux/recvmsg.c:27
#1  __libc_recvmsg (fd=3, msg=0x7f80c48246b0, flags=0) at ../sysdeps/unix/sysv/linux/recvmsg.c:41
#2  0x00007f80c4992eec in ?? () from /lib/x86_64-linux-gnu/liblttng-ust.so.1
#3  0x00007f80c4967f42 in ?? () from /lib/x86_64-linux-gnu/liblttng-ust.so.1
#4  0x00007f80c4c23b43 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:442
#5  0x00007f80c4cb5a00 in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:81

Thread 1 (Thread 0x7f80c4830680 (LWP 1526191) "publisher_membe"):
#0  futex_wait (private=0, expected=2, futex_word=0x7ffdd8094ce0) at ../sysdeps/nptl/futex-internal.h:146
#1  __GI___lll_lock_wait (futex=futex@entry=0x7ffdd8094ce0, private=0) at ./nptl/lowlevellock.c:49
#2  0x00007f80c4c27082 in lll_mutex_lock_optimized (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:48
#3  ___pthread_mutex_lock (mutex=0x7ffdd8094ce0) at ./nptl/pthread_mutex_lock.c:93
#4  0x00007f80c5a84a01 in __gthread_mutex_lock (__mutex=0x7ffdd8094ce0) at /usr/include/x86_64-linux-gnu/c++/11/bits/gthr-default.h:749
#5  0x00007f80c5a872b2 in std::mutex::lock (this=0x7ffdd8094ce0) at /usr/include/c++/11/bits/std_mutex.h:100
#6  0x00007f80c5a87900 in std::lock_guard<std::mutex>::lock_guard (this=0x7ffdd8094848, __m=...) at /usr/include/c++/11/bits/std_mutex.h:229
#7  0x00007f80c5ac7169 in rclcpp::executors::MultiThreadedExecutor::run (this=0x7ffdd8094aa0, this_thread_number=15) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp:81
#8  0x00007f80c5ac6fd5 in rclcpp::executors::MultiThreadedExecutor::spin (this=0x7ffdd8094aa0) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/rclcpp/rclcpp/src/rclcpp/executors/multi_threaded_executor.cpp:62
#9  0x000055c5db6b191b in main (argc=1, argv=0x7ffdd8094e58) at /home/chenlh/Projects/ROS2/ros2-humble/src/ros2/examples/rclcpp/topics/minimal_publisher/member_function.cpp:64

@iuhilnehc-ynos
Copy link
Contributor

The notification of https://github.com/ros2/rclcpp/blob/33cbd76c07dc9a30e8dbeecd5f5e70057122a369/rclcpp/src/rclcpp/executor.cpp#L540 might be lost.

Let me try to explain this issue.

About the timer callback called in multiple thread executor, we assume that thread a gets the timer timeout and calls the timer callback and then calls the interrupt_guard_condition_.trigger(); to trigger the interrupt_guard_condition_ for wait_set of thread b, so thread b can get the notification to continue to add the timer into waitset. If the interrupt_guard_condition_.trigger(); notification is lost, thread b can't continue to add the timer into its waitset. That's why thread 25 in #650 (comment) wait without a timeout.

thread a of executor:

MultiThreadedExecutor::run
  for {
    {
      std::lock_guard wait_lock{wait_mutex_};
      if (!get_next_executable(any_exec, next_exec_timeout_)) {
        continue;
      }
    }

    execute_any_executable         // keep the `CallbackGroup::can_be_taken_from_(true)` and call timer_callback
                                   // and then call `interrupt_guard_condition_.trigger();` to trigger the waitset in thread b
  }
  
  

thread b of executor:

MultiThreadedExecutor::run
  for {
    {
      std::lock_guard wait_lock{wait_mutex_};
      if (!get_next_executable(any_exec, next_exec_timeout_)) {             // wait without timer until the interrupt_guard_condition triggered
        continue;
      }
    }

    execute_any_executable
  }

I think it's related to eProsima/Fast-DDS#3087 .

@fujitatomoya
Copy link
Collaborator

@iuhilnehc-ynos thanks for checking on this, #650 (comment) makes sense to me. So this could be wait forever problem but deadlock. did you confirm that eProsima/Fast-DDS#3087 can solve this problem with reproducible test sample?

@iuhilnehc-ynos
Copy link
Contributor

this could be wait forever problem but deadlock.

Yes, it's not a deadlock.

did you confirm that eProsima/Fast-DDS#3087 can solve this problem with reproducible test sample?

Yes. Two ways I confirmed. (a. the example ran from yesterday to this morning and it seems good till now. b. rerun it after 20 seconds many times.)

@hplatou
Copy link
Author

hplatou commented Dec 21, 2022

I can also confirm that this resolves my problems. Thanks again!

@hplatou
Copy link
Author

hplatou commented Jan 2, 2023

Any chance this will be fixed for the next package sync of Humble?

@fujitatomoya
Copy link
Collaborator

Any chance this will be fixed for the next package sync of Humble?

This is a question for eProsima. https://github.com/ros2/ros2/blob/00f3ba9f73916a5eab322710edaaf197f0f10e31/ros2.repos#L34-L37 uses 2.6.x branch for humble. if the fix can be backported to 2.6.x branch, we can fix this problem ROS 2 humble as well.

CC: @MiguelCompany

@MiguelCompany
Copy link
Collaborator

@fujitatomoya
Fix for rolling is currently eProsima/Fast-DDS#3194
See eProsima/Fast-DDS#3195 for the backport to Fast-DDS 2.6.x (i.e. Humble)

@MiguelCompany
Copy link
Collaborator

@hplatou The fix on Fast DDS has already been released on the Humble binaries.

Do you think this can be closed?

@hplatou
Copy link
Author

hplatou commented Feb 12, 2023

Yes, I can confirm that the released version has resolved the issue. Thanks!

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

4 participants