ros2 / rclpy

rclpy (ROS Client Library for Python)
Apache License 2.0
269 stars 221 forks source link

Node crashes when importing Gstreamer python bindings #1149

Open s-hall opened 11 months ago

s-hall commented 11 months ago

Bug report

Importing Gstreamer python bindings seems to make rclpy segfault or abort when trying to create a node.

Required Info:

Steps to reproduce issue

Minimal example:

import gi
import rclpy

rclpy.init()
print("init")

# tmp_node = rclpy.create_node("fixed")
# tmp_node.destroy_node()
# del tmp_node

gi.require_version("Gst", "1.0")
from gi.repository import Gst

print("before node")
node = rclpy.create_node("gstreamer_crash")
print("after node")
rclpy.spin(node)

Running a container from a directory with the above script, gst_rclpy.py: docker run --rm -it -v .:/test ros:humble bash Inside:

apt update && apt install -y python3-gi python3-gst-1.0
python3 /test/gst_rclpy.py

Output:

init
before node
Segmentation fault (core dumped)

Expected behavior

No crash.

Actual behavior

Quickly tested on different distributions; it works on ros:foxy and ros:galactic, and crashes on ros:humble and onwards. Also, I happened to notice if a node is created before importing Gstreamer, it seems to avoid the crash (though this didn't seem to be a reliable fix in our actual application).

fujitatomoya commented 11 months ago

@iuhilnehc-ynos @Barry-Xu-2018 can you check this if you have bandwidth? it is not unlikely that application uses gstreamer plugin with ROS 2.

iuhilnehc-ynos commented 11 months ago

I can reproduce this issue followed by https://github.com/ros2/rclpy/issues/1149#issue-1837424580, but this issue can't happen on rmw_cyclonedds_cpp.

After installing the debug symbols packages, got the backtrace at the point of Segmentation fault by running the gst_rclpy.py below,

(gdb) bt
#0  0x00007ffff6702580 in ?? () from /lib/x86_64-linux-gnu/libgcc_s.so.1
#1  0x00007ffff670273f in __gcc_personality_v0 () from /lib/x86_64-linux-gnu/libgcc_s.so.1
#2  0x00007ffff4d0bfe9 in __libunwind_Unwind_Resume () from /lib/x86_64-linux-gnu/libunwind.so.8
#3  0x00007ffff56d6f8a in __gnu_cxx::new_allocator<char>::deallocate (__t=<optimized out>, __p=<optimized out>, this=<optimized out>, 
    this=<optimized out>, __p=<optimized out>, __t=<optimized out>) at /usr/include/c++/11/ext/new_allocator.h:145
#4  std::allocator_traits<std::allocator<char> >::deallocate (__n=<optimized out>, __p=<optimized out>, __a=..., __a=..., __p=<optimized out>, 
    __n=<optimized out>) at /usr/include/c++/11/bits/alloc_traits.h:496
#5  std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >::_M_destroy (__size=<optimized out>, this=<optimized out>, 
    this=<optimized out>, __size=<optimized out>) at /usr/include/c++/11/bits/basic_string.h:245
#6  std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >::_M_dispose (this=<optimized out>, this=<optimized out>)
    at /usr/include/c++/11/bits/basic_string.h:240
#7  std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >::~basic_string (this=<optimized out>, this=<optimized out>)
    at /usr/include/c++/11/bits/basic_string.h:672
#8  boost::interprocess::shared_memory_object::shared_memory_object (this=0x7fffffff4cb0, name=<optimized out>, mode=<optimized out>)
    at ./thirdparty/boost/include/boost/interprocess/shared_memory_object.hpp:83
#9  0x00007ffff5b3e40d in boost::interprocess::ipcdetail::managed_open_or_create_impl<boost::interprocess::shared_memory_object, 16ul, true, false>::priv_open_or_create<boost::interprocess::ipcdetail::create_open_func<boost::interprocess::ipcdetail::basic_managed_memory_impl<char, boost::interprocess::rbtree_best_fit<boost::interprocess::mutex_family, boost::interprocess::offset_ptr<void, unsigned int, unsigned long, 0ul>, 0ul>, boost::interprocess::iset_index, 16ul> > >(boost::interprocess::ipcdetail::create_enum_t, char const* const&, unsigned long, boost::interprocess::mode_t, void const*, boost::interprocess::permissions const&, boost::interprocess::ipcdetail::create_open_func<boost::interprocess::ipcdetail::basic_managed_memory_impl<char, boost::interprocess::rbtree_best_fit<boost::interprocess::mutex_family, boost::interprocess::offset_ptr<void, unsigned int, unsigned long, 0ul>, 0ul>, boost::interprocess::iset_index, 16ul> >) [clone .constprop.0] (this=this@entry=0x555555f57408, type=type@entry=boost::interprocess::ipcdetail::DoOpen, 
    id=@0x7fffffff4dc0: 0x555555f57430 "fastrtps_port14412", size=size@entry=0, mode=mode@entry=boost::interprocess::read_write, perm=..., 
    construct_func=..., addr=0x0) at ./thirdparty/boost/include/boost/interprocess/detail/managed_open_or_create_impl.hpp:339
#10 0x00007ffff5b36a75 in boost::interprocess::ipcdetail::managed_open_or_create_impl<boost::interprocess::shared_memory_object, 16ul, true, false>::managed_open_or_create_impl<boost::interprocess::ipcdetail::create_open_func<boost::interprocess::ipcdetail::basic_managed_memory_impl<char, boost::interprocess::rbtree_best_fit<boost::interprocess::mutex_family, boost::interprocess::offset_ptr<void, unsigned int, unsigned long, 0ul>, 0ul>, boost::interprocess::iset_index, 16ul> > > (construct_func=..., construct_func=..., addr=0x0, mode=boost::interprocess::read_write, 
    id=@0x7fffffff4dc0: 0x555555f57430 "fastrtps_port14412", this=0x555555f57408)
    at ./thirdparty/boost/include/boost/interprocess/detail/managed_open_or_create_impl.hpp:202
#11 boost::interprocess::basic_managed_shared_memory<char, boost::interprocess::rbtree_best_fit<boost::interprocess::mutex_family, boost::interprocess::offset_ptr<void, unsigned int, unsigned long, 0ul>, 0ul>, boost::interprocess::iset_index>::basic_managed_shared_memory (addr=0x0, name=<optimized out>, 
    this=0x555555f57400) at ./thirdparty/boost/include/boost/interprocess/managed_shared_memory.hpp:151
#12 eprosima::fastdds::rtps::SharedSegment<boost::interprocess::basic_managed_shared_memory<char, boost::interprocess::rbtree_best_fit<boost::interprocess::mutex_family, boost::interprocess::offset_ptr<void, unsigned int, unsigned long, 0ul>, 0ul>, boost::interprocess::iset_index>, boost::interprocess::shared_memory_object>::SharedSegment(boost::interprocess::open_only_t, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&) [clone .constprop.0] (this=0x555555e3c400, name=...) at ./src/cpp/utils/shared_memory/SharedMemSegment.hpp:272
--Type <RET> for more, q to quit, c to continue without paging--c
#13 0x00007ffff59eeb77 in eprosima::fastdds::rtps::SharedMemGlobal::open_port_internal (this=0x555555e89950, port_id=14412, max_buffer_descriptors=512, healthy_check_timeout_ms=1000, open_mode=eprosima::fastdds::rtps::SharedMemGlobal::Port::OpenMode::ReadExclusive, regenerating_port=std::shared_ptr<eprosima::fastdds::rtps::SharedMemGlobal::Port> (empty) = {...}) at ./src/cpp/rtps/transport/shared_mem/SharedMemGlobal.hpp:1018
#14 0x00007ffff59f991c in eprosima::fastdds::rtps::SharedMemGlobal::open_port (open_mode=eprosima::fastdds::rtps::SharedMemGlobal::Port::OpenMode::ReadExclusive, healthy_check_timeout_ms=<optimized out>, max_buffer_descriptors=<optimized out>, port_id=<optimized out>, this=0x555555e89950) at ./src/cpp/rtps/transport/shared_mem/SharedMemGlobal.hpp:931
#15 eprosima::fastdds::rtps::SharedMemManager::open_port (open_mode=eprosima::fastdds::rtps::SharedMemGlobal::Port::OpenMode::ReadExclusive, healthy_check_timeout_ms=<optimized out>, max_descriptors=<optimized out>, port_id=<optimized out>, this=0x555555e898d0) at ./src/cpp/rtps/transport/shared_mem/SharedMemManager.hpp:985
#16 eprosima::fastdds::rtps::SharedMemTransport::CreateInputChannelResource (this=0x555555ea4700, locator=..., maxMsgSize=<optimized out>, receiver=0x555555e6bf50) at ./src/cpp/rtps/transport/shared_mem/SharedMemTransport.cpp:319
#17 0x00007ffff59f9025 in eprosima::fastdds::rtps::SharedMemTransport::OpenInputChannel (this=0x555555ea4700, locator=..., receiver=0x555555e6bf50, maxMsgSize=4294967295) at ./src/cpp/rtps/transport/shared_mem/SharedMemTransport.cpp:134
#18 0x00007ffff57c4670 in eprosima::fastrtps::rtps::ReceiverResource::ReceiverResource (this=<optimized out>, transport=..., locator=..., max_recv_buffer_size=<optimized out>, this=<optimized out>, transport=..., locator=..., max_recv_buffer_size=<optimized out>) at ./src/cpp/rtps/network/ReceiverResource.cpp:41
#19 0x00007ffff57c488e in eprosima::fastrtps::rtps::NetworkFactory::BuildReceiverResources (this=<optimized out>, local=..., returned_resources_list=std::vector of length 0, capacity 1, receiver_max_message_size=4294967295) at /usr/include/c++/11/bits/unique_ptr.h:173
#20 0x00007ffff57c9e87 in eprosima::fastrtps::rtps::RTPSParticipantImpl::createReceiverResources (this=0x555555f593e0, Locator_list=..., ApplyMutation=true, RegisterReceiver=false) at ./src/cpp/rtps/participant/RTPSParticipantImpl.cpp:1635
#21 0x00007ffff57caf3c in eprosima::fastrtps::rtps::RTPSParticipantImpl::RTPSParticipantImpl (this=<optimized out>, domain_id=<optimized out>, PParam=..., guidP=..., persistence_guid=..., par=<optimized out>, plisten=<optimized out>, this=<optimized out>, domain_id=<optimized out>, PParam=..., guidP=..., persistence_guid=..., par=<optimized out>, plisten=<optimized out>) at ./src/cpp/rtps/participant/RTPSParticipantImpl.cpp:353
#22 0x00007ffff57cbd59 in eprosima::fastrtps::rtps::RTPSParticipantImpl::RTPSParticipantImpl (this=<optimized out>, domain_id=<optimized out>, PParam=..., guidP=..., par=<optimized out>, plisten=<optimized out>, this=<optimized out>, domain_id=<optimized out>, PParam=..., guidP=..., par=<optimized out>, plisten=<optimized out>) at ./src/cpp/rtps/participant/RTPSParticipantImpl.cpp:440
#23 0x00007ffff57d7930 in eprosima::fastrtps::rtps::RTPSDomain::createParticipant (domain_id=28, enabled=<optimized out>, attrs=..., listen=0x555555f593c0) at ./src/cpp/rtps/RTPSDomain.cpp:182
#24 0x00007ffff5838070 in eprosima::fastdds::dds::DomainParticipantImpl::enable (this=0x555555f58840) at ./src/cpp/fastdds/domain/DomainParticipantImpl.cpp:304
#25 0x00007ffff5832026 in eprosima::fastdds::dds::DomainParticipant::enable (this=0x555555e71810) at ./src/cpp/fastdds/domain/DomainParticipant.cpp:95
#26 eprosima::fastdds::dds::DomainParticipant::enable (this=0x555555e71810) at ./src/cpp/fastdds/domain/DomainParticipant.cpp:87
#27 eprosima::fastdds::dds::DomainParticipantFactory::create_participant (this=0x7ffff5c9cb00 <eprosima::fastdds::dds::DomainParticipantFactory::get_instance()::instance>, did=did@entry=28, qos=..., listen=<optimized out>, mask=...) at ./src/cpp/fastdds/domain/DomainParticipantFactory.cpp:249
#28 0x00007ffff5d309f3 in __create_participant (identifier=0x7ffff5da6000 "rmw_fastrtps_cpp", domainParticipantQos=..., leave_middleware_default_qos=<optimized out>, publishing_mode=publishing_mode_t::SYNCHRONOUS, common_context=0x555555ec1d80, domain_id=28) at ./src/participant.cpp:99
#29 0x00007ffff5d3ca7d in rmw_fastrtps_shared_cpp::create_participant (identifier=identifier@entry=0x7ffff5da6000 "rmw_fastrtps_cpp", domain_id=28, security_options=security_options@entry=0x555555d86f18, localhost_only=<optimized out>, enclave=<optimized out>, common_context=common_context@entry=0x555555ec1d80) at ./src/participant.cpp:284
#30 0x00007ffff5d8eaa3 in init_context_impl (context=0x555555d86ef0) at /usr/include/c++/11/bits/std_function.h:211
#31 0x00007ffff5d97120 in rmw_fastrtps_cpp::increment_context_impl_ref_count (context=0x555555d86ef0) at ./src/init_rmw_context_impl.cpp:202
#32 rmw_create_node (context=0x555555d86ef0, name=0x7fffffffd310 "gstreamer_crash", namespace_=0x7ffff69a8866 "/") at ./src/rmw_node.cpp:60
#33 0x00007ffff69a085a in rcl_node_init () from /opt/ros/humble/lib/librcl.so
#34 0x00007ffff7004117 in ?? () from /opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/_rclpy_pybind11.cpython-310-x86_64-linux-gnu.so
#35 0x00007ffff70076e4 in ?? () from /opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/_rclpy_pybind11.cpython-310-x86_64-linux-gnu.so
#36 0x00007ffff6fcf1d9 in ?? () from /opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/_rclpy_pybind11.cpython-310-x86_64-linux-gnu.so
#37 0x00005555556afb5e in ?? ()
#38 0x00005555556a67db in _PyObject_MakeTpCall ()
#39 0x00005555556be7c0 in ?? ()
#40 0x00005555556babbb in ?? ()
#41 0x00005555556a6b8b in ?? ()
#42 0x00007ffff6fcdf76 in ?? () from /opt/ros/humble/local/lib/python3.10/dist-packages/rclpy/_rclpy_pybind11.cpython-310-x86_64-linux-gnu.so
#43 0x00005555556a67db in _PyObject_MakeTpCall ()
#44 0x000055555569f48e in _PyEval_EvalFrameDefault ()
#45 0x00005555556b03ac in _PyFunction_Vectorcall ()
#46 0x00005555556a5a0d in _PyObject_FastCallDictTstate ()
#47 0x00005555556ba594 in ?? ()
#48 0x00005555556a677c in _PyObject_MakeTpCall ()
#49 0x000055555569fe1c in _PyEval_EvalFrameDefault ()
#50 0x00005555556b03ac in _PyFunction_Vectorcall ()
#51 0x000055555569ea72 in _PyEval_EvalFrameDefault ()
#52 0x0000555555695766 in ?? ()
#53 0x000055555578d456 in PyEval_EvalCode ()
#54 0x00005555557b9f08 in ?? ()
#55 0x00005555557b2d5b in ?? ()
#56 0x00005555557b9c55 in ?? ()
#57 0x00005555557b9138 in _PyRun_SimpleFileObject ()
#58 0x00005555557b8e33 in _PyRun_AnyFileObject ()
#59 0x00005555557aa0ae in Py_RunMain ()
#60 0x000055555578034d in Py_BytesMain ()
#61 0x00007ffff7c82d90 in __libc_start_call_main (main=main@entry=0x555555780310, argc=argc@entry=2, argv=argv@entry=0x7fffffffe3d8) at ../sysdeps/nptl/libc_start_call_main.h:58
#62 0x00007ffff7c82e40 in __libc_start_main_impl (main=0x555555780310, argc=2, argv=0x7fffffffe3d8, init=<optimized out>, fini=<optimized out>, rtld_fini=<optimized out>, stack_end=0x7fffffffe3c8) at ../csu/libc-start.c:392
#63 0x0000555555780245 in _start ()
iuhilnehc-ynos commented 11 months ago
(gdb) r
The program being debugged has been started already.
Start it from the beginning? (y or n) y
Starting program: /usr/bin/python3 gst_rclpy.py
[Thread debugging using libthread_db enabled]
Using host libthread_db library "/lib/x86_64-linux-gnu/libthread_db.so.1".
[New Thread 0x7ffff4fde640 (LWP 3505394)]
[New Thread 0x7ffff25ff640 (LWP 3506068)]
init
before node
[New Thread 0x7ffff0e70640 (LWP 3506305)]
[New Thread 0x7ffff05e8640 (LWP 3506306)]
[New Thread 0x7fffefde7640 (LWP 3506307)]
[New Thread 0x7fffef5e6640 (LWP 3506308)]
[New Thread 0x7fffeede5640 (LWP 3506309)]

Thread 1 "python3" hit Breakpoint 2, boost::interprocess::shared_memory_object::shared_memory_object (this=0x7fffffff1720, name=0x55555600e410 "fastrtps_port14411", mode=boost::interprocess::read_write) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/shared_memory_object.hpp:83
83     {  this->priv_open_or_create(ipcdetail::DoOpen, name, mode, permissions());  }
(gdb) bt
#0  boost::interprocess::shared_memory_object::shared_memory_object(boost::interprocess::open_only_t, char const*, boost::interprocess::mode_t) (this=0x7fffffff1720, name=0x55555600e410 "fastrtps_port14411", mode=boost::interprocess::read_write) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/shared_memory_object.hpp:83
#1  0x00007ffff37f1d52 in boost::interprocess::ipcdetail::managed_open_or_create_impl<boost::interprocess::shared_memory_object, 16ul, true, false>::priv_open_or_create<boost::interprocess::ipcdetail::create_open_func<boost::interprocess::ipcdetail::basic_managed_memory_impl<char, boost::interprocess::rbtree_best_fit<boost::interprocess::mutex_family, boost::interprocess::offset_ptr<void, unsigned int, unsigned long, 0ul>, 0ul>, boost::interprocess::iset_index, 16ul> > >(boost::interprocess::ipcdetail::create_enum_t, char const* const&, unsigned long, boost::interprocess::mode_t, void const*, boost::interprocess::permissions const&, boost::interprocess::ipcdetail::create_open_func<boost::interprocess::ipcdetail::basic_managed_memory_impl<char, boost::interprocess::rbtree_best_fit<boost::interprocess::mutex_family, boost::interprocess::offset_ptr<void, unsigned int, unsigned long, 0ul>, 0ul>, boost::interprocess::iset_index, 16ul> >) (this=0x55555600e3e8, type=boost::interprocess::ipcdetail::DoOpen, id=@0x7fffffff1800: 0x55555600e410 "fastrtps_port14411", size=0, mode=boost::interprocess::read_write, addr=0x0, perm=..., construct_func=...) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/detail/managed_open_or_create_impl.hpp:339
#2  0x00007ffff37f0994 in boost::interprocess::ipcdetail::managed_open_or_create_impl<boost::interprocess::shared_memory_object, 16ul, true, false>::managed_open_or_create_impl<boost::interprocess::ipcdetail::create_open_func<boost::interprocess::ipcdetail::basic_managed_memory_impl<char, boost::interprocess::rbtree_best_fit<boost::interprocess::mutex_family, boost::interprocess::offset_ptr<void, unsigned int, unsigned long, 0ul>, 0ul>, boost::interprocess::iset_index, 16ul> > >(boost::interprocess::open_only_t, char const* const&, boost::interprocess::mode_t, void const*, boost::interprocess::ipcdetail::create_open_func<boost::interprocess::ipcdetail::basic_managed_memory_impl<char, boost::interprocess::rbtree_best_fit<boost::interprocess::mutex_family, boost::interprocess::offset_ptr<void, unsigned int, unsigned long, 0ul>, 0ul>, boost::interprocess::iset_index, 16ul> > const&) (this=0x55555600e3e8, id=@0x7fffffff1800: 0x55555600e410 "fastrtps_port14411", mode=boost::interprocess::read_write, addr=0x0, construct_func=...) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/detail/managed_open_or_create_impl.hpp:202
#3  0x00007ffff38442bd in boost::interprocess::basic_managed_shared_memory<char, boost::interprocess::rbtree_best_fit<boost::interprocess::mutex_family, boost::interprocess::offset_ptr<void, unsigned int, unsigned long, 0ul>, 0ul>, boost::interprocess::iset_index>::basic_managed_shared_memory(boost::interprocess::open_only_t, char const*, void const*) (this=0x55555600e3e0, name=0x55555600e410 "fastrtps_port14411", addr=0x0) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/managed_shared_memory.hpp:151
#4  0x00007ffff3843ec2 in eprosima::fastdds::rtps::SharedSegment<boost::interprocess::basic_managed_shared_memory<char, boost::interprocess::rbtree_best_fit<boost::interprocess::mutex_family, boost::interprocess::offset_ptr<void, unsigned int, unsigned long, 0ul>, 0ul>, boost::interprocess::iset_index>, boost::interprocess::shared_memory_object>::SharedSegment(boost::interprocess::open_only_t, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&) (this=0x555555fddff0, name="fastrtps_port14411") at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/utils/shared_memory/SharedMemSegment.hpp:341
#5  0x00007ffff3dc0193 in eprosima::fastdds::rtps::SharedMemGlobal::open_port_internal(unsigned int, unsigned int, unsigned int, eprosima::fastdds::rtps::SharedMemGlobal::Port::OpenMode, std::shared_ptr<eprosima::fastdds::rtps::SharedMemGlobal::Port>) (this=0x555555c2f130, port_id=14411, max_buffer_descriptors=512, healthy_check_timeout_ms=1000, open_mode=eprosima::fastdds::rtps::SharedMemGlobal::Port::OpenMode::ReadExclusive, regenerating_port=std::shared_ptr<eprosima::fastdds::rtps::SharedMemGlobal::Port> (empty) = {...}) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/transport/shared_mem/SharedMemGlobal.hpp:1078
...

The exception https://github.com/eProsima/Fast-DDS/blob/2bb06109920a886fda3ec39c8c6d333eaa4df011/thirdparty/boost/include/boost/interprocess/shared_memory_object.hpp#L363 happened at frame 1 should be propagated to https://github.com/eProsima/Fast-DDS/blob/7cf43a62cabc3124721258f02c9257f451dd1971/src/cpp/rtps/transport/shared_mem/SharedMemGlobal.hpp#L1078 that will be caught at https://github.com/eProsima/Fast-DDS/blob/7cf43a62cabc3124721258f02c9257f451dd1971/src/cpp/rtps/transport/shared_mem/SharedMemGlobal.hpp#L1165 in frame 5.

but after executing finish the frame 1, the output shows throwing the boost::interprocess::interprocess_exception that is not caught.

(gdb) fin
Run till exit from #0  boost::interprocess::shared_memory_object::shared_memory_object (this=0x7fffffff1720, name=0x55555600e410 "fastrtps_port14411", mode=boost::interprocess::read_write) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/shared_memory_object.hpp:83
terminate called after throwing an instance of 'boost::interprocess::interprocess_exception'
  what():  No such file or directory

Thread 1 "python3" received signal SIGABRT, Aborted.
__pthread_kill_implementation (no_tid=0, signo=6, threadid=140737352327616) at ./nptl/pthread_kill.c:44
44  ./nptl/pthread_kill.c: No such file or directory.

Very interesting, right?

iuhilnehc-ynos commented 11 months ago

I am afraid that the root issue might be related to either python3.10 or python3-gi python3-gst-1.0.

I have confirmed that the gst_rclpy.py run well with RMW_IMPLEMENTATION=rmw_fastrtps_cpp on ROS 2 source galactic which is built on ubuntu20(python3.8), but it failed to run on the ROS 2 source galactic, which is the same source code, built on ubuntu22(python3.10).

iuhilnehc-ynos commented 11 months ago

And gst_rclpy.py can run well with ROS 2 source humble built on ubuntu20(python3.8).

iuhilnehc-ynos commented 11 months ago

I don't know what kinds of situations/steps can cause the call stack or stack frames to be corrupted.

@fujitatomoya @clalancette @MiguelCompany Do you have any suggestions?

clalancette commented 11 months ago

One idea I have is that maybe the ABI between the vendored copy of boost in fastrtps, and boost from the system, are colliding. That only makes sense if gstreamer depends on boost, which I don't know if that is the case.

@MiguelCompany Is it possible to have Fast-DDS use the system copy of boost, rather than the vendored copy? If so, how do you do that?

fujitatomoya commented 11 months ago

according to pmap for shared libraries, boost is not linked in the core.

(gdb) info sharedlibrary
From                To                  Syms Read   Shared Object Library
0x00007fb6c36793a0  0x00007fb6c36f48e8  No          /lib/x86_64-linux-gnu/libm.so.6
0x00007fb6c363c290  0x00007fb6c365a5a7  No          /lib/x86_64-linux-gnu/libexpat.so.1
0x00007fb6c361e280  0x00007fb6c362ec14  No          /lib/x86_64-linux-gnu/libz.so.1
0x00007fb6c341c700  0x00007fb6c35aeabd  No          /lib/x86_64-linux-gnu/libc.so.6
0x00007fb6c3773090  0x00007fb6c379c335  No          /lib64/ld-linux-x86-64.so.2
0x00007fb6c37555a0  0x00007fb6c375720b  No          /usr/lib/python3.10/lib-dynload/_bz2.cpython-310-x86_64-linux-gnu.so
0x00007fb6c2c10280  0x00007fb6c2c1c563  No          /lib/x86_64-linux-gnu/libbz2.so.1.0
0x00007fb6c2c29920  0x00007fb6c2c2c891  No          /usr/lib/python3.10/lib-dynload/_lzma.cpython-310-x86_64-linux-gnu.so
0x00007fb6c2bd53c0  0x00007fb6c2bef0de  No          /lib/x86_64-linux-gnu/liblzma.so.5
0x00007fb6c2946300  0x00007fb6c296f43b  No          /usr/lib/python3/dist-packages/gi/_gi.cpython-310-x86_64-linux-gnu.so
0x00007fb6c2817b20  0x00007fb6c28a4f22  No          /lib/x86_64-linux-gnu/libglib-2.0.so.0
0x00007fb6c27a8fd0  0x00007fb6c27dac5e  No          /lib/x86_64-linux-gnu/libgobject-2.0.so.0
0x00007fb6c277e350  0x00007fb6c278deba  No          /lib/x86_64-linux-gnu/libgirepository-1.0.so.1
0x00007fb6c2e3b460  0x00007fb6c2e41392  No          /lib/x86_64-linux-gnu/libffi.so.8
0x00007fb6c27022a0  0x00007fb6c27565b0  No          /lib/x86_64-linux-gnu/libpcre.so.3
0x00007fb6c2e344a0  0x00007fb6c2e35433  No          /lib/x86_64-linux-gnu/libgmodule-2.0.so.0
0x00007fb6c25663e0  0x00007fb6c266f0cd  No          /lib/x86_64-linux-gnu/libgio-2.0.so.0
0x00007fb6c24ec290  0x00007fb6c2516dc1  No          /lib/x86_64-linux-gnu/libmount.so.1
0x00007fb6c24bdfc0  0x00007fb6c24d667d  No          /lib/x86_64-linux-gnu/libselinux.so.1
0x00007fb6c2487d10  0x00007fb6c24a6831  No          /lib/x86_64-linux-gnu/libblkid.so.1
0x00007fb6c23eb2e0  0x00007fb6c2455adf  No          /lib/x86_64-linux-gnu/libpcre2-8.so.0
0x00007fb6c2e53140  0x00007fb6c2e5342d  No          /usr/lib/python3.10/lib-dynload/_opcode.cpython-310-x86_64-linux-gnu.so
0x00007fb6c22b2020  0x00007fb6c22de23c  No          /usr/lib/python3/dist-packages/yaml/_yaml.cpython-310-x86_64-linux-gnu.so
0x00007fb6c228c240  0x00007fb6c22a4a0d  No          /lib/x86_64-linux-gnu/libyaml-0.so.2
0x00007fb6c2029f80  0x00007fb6c21bbdee  No          /root/ros2_ws/colcon_ws/install/rclpy/lib/python3.10/site-packages/rclpy/_rclpy_pybind11.cpython-310-x86_64-linux-gnu.so
0x00007fb6c1ffcc20  0x00007fb6c2004aa8  No          /root/ros2_ws/colcon_ws/install/rcl_action/lib/librcl_action.so
0x00007fb6c2c045c0  0x00007fb6c2c08f4c  No          /root/ros2_ws/colcon_ws/install/rcl_lifecycle/lib/librcl_lifecycle.so
0x00007fb6c1a80c40  0x00007fb6c1d2f83e  No          /lib/x86_64-linux-gnu/libpython3.10.so.1.0
0x00007fb6c19d1d00  0x00007fb6c19f8d22  No          /root/ros2_ws/colcon_ws/install/rcl/lib/librcl.so
0x00007fb6c2e4e120  0x00007fb6c2e4e5a9  No          /root/ros2_ws/colcon_ws/install/rcl_logging_interface/lib/librcl_logging_interface.so
0x00007fb6c19b7820  0x00007fb6c19be8a1  No          /root/ros2_ws/colcon_ws/install/rcl_yaml_param_parser/lib/librcl_yaml_param_parser.so
0x00007fb6c19ab3e0  0x00007fb6c19afc2c  No          /root/ros2_ws/colcon_ws/install/rmw_implementation/lib/librmw_implementation.so
0x00007fb6c199e600  0x00007fb6c19a2f19  No          /root/ros2_ws/colcon_ws/install/rmw/lib/librmw.so
0x00007fb6c1995040  0x00007fb6c1995569  No          /root/ros2_ws/colcon_ws/install/lifecycle_msgs/lib/liblifecycle_msgs__ro--Type <RET> for more, q to quit, c to continue without paging--
sidl_typesupport_c.so
0x00007fb6c1972f60  0x00007fb6c1981d40  No          /root/ros2_ws/colcon_ws/install/rcutils/lib/librcutils.so
0x00007fb6c17e3420  0x00007fb6c18ebfc2  No          /lib/x86_64-linux-gnu/libstdc++.so.6
0x00007fb6c1724660  0x00007fb6c173a805  No          /lib/x86_64-linux-gnu/libgcc_s.so.1
0x00007fb6c1705080  0x00007fb6c17140f7  No          /root/ros2_ws/colcon_ws/install/rosidl_runtime_c/lib/librosidl_runtime_c.so
0x00007fb6c16dc260  0x00007fb6c16f1cef  No          /root/ros2_ws/colcon_ws/install/tracetools/lib/libtracetools.so
0x00007fb6c16b45e0  0x00007fb6c16c229c  No          /root/ros2_ws/colcon_ws/install/lifecycle_msgs/lib/liblifecycle_msgs__rosidl_generator_c.so
0x00007fb6c169db50  0x00007fb6c16a2a29  No          /root/ros2_ws/colcon_ws/install/rcl_logging_spdlog/lib/librcl_logging_spdlog.so
0x00007fb6c1682040  0x00007fb6c1682ba0  No          /root/ros2_ws/colcon_ws/install/rcl_interfaces/lib/librcl_interfaces__rosidl_typesupport_c.so
0x00007fb6c1661ce0  0x00007fb6c1670571  No          /root/ros2_ws/colcon_ws/install/rosidl_dynamic_typesupport/lib/librosidl_dynamic_typesupport.so
0x00007fb6c1655040  0x00007fb6c16553dc  No          /root/ros2_ws/colcon_ws/install/type_description_interfaces/lib/libtype_description_interfaces__rosidl_typesupport_c.so
0x00007fb6c163ee00  0x00007fb6c1646f85  No          /root/ros2_ws/colcon_ws/install/type_description_interfaces/lib/libtype_description_interfaces__rosidl_generator_c.so
0x00007fb6c162ddb0  0x00007fb6c1631fff  No          /root/ros2_ws/colcon_ws/install/ament_index_cpp/lib/libament_index_cpp.so
0x00007fb6c1613a80  0x00007fb6c161afb7  No          /root/ros2_ws/colcon_ws/install/rcpputils/lib/librcpputils.so
0x00007fb6c2e485e0  0x00007fb6c2e49c3d  No          /root/ros2_ws/colcon_ws/install/rosidl_typesupport_c/lib/librosidl_typesupport_c.so
0x00007fb6c158d220  0x00007fb6c15d328b  No          /lib/x86_64-linux-gnu/liblttng-ust.so.1
0x00007fb6c157c2a0  0x00007fb6c157cefc  No          /root/ros2_ws/colcon_ws/install/service_msgs/lib/libservice_msgs__rosidl_generator_c.so
0x00007fb6c1575280  0x00007fb6c1576565  No          /root/ros2_ws/colcon_ws/install/builtin_interfaces/lib/libbuiltin_interfaces__rosidl_generator_c.so
0x00007fb6c1529de0  0x00007fb6c155cfd7  No          /lib/x86_64-linux-gnu/libspdlog.so.1
0x00007fb6c14ba2c0  0x00007fb6c14da49e  No          /root/ros2_ws/colcon_ws/install/rcl_interfaces/lib/librcl_interfaces__rosidl_generator_c.so
0x00007fb6c1497800  0x00007fb6c149c822  No          /lib/x86_64-linux-gnu/libnuma.so.1
0x00007fb6c14886e0  0x00007fb6c148ebe7  No          /lib/x86_64-linux-gnu/liblttng-ust-common.so.1
0x00007fb6c146a460  0x00007fb6c14705ee  No          /lib/x86_64-linux-gnu/liblttng-ust-tracepoint.so.1
0x00007fb6c144b710  0x00007fb6c1460a5f  No          /lib/x86_64-linux-gnu/libfmt.so.8
0x00007fb6c022a170  0x00007fb6c027bb83  No          /root/ros2_ws/colcon_ws/install/rmw_fastrtps_cpp/lib/librmw_fastrtps_cpp.so
0x00007fb6c0120d30  0x00007fb6c01b616c  No          /root/ros2_ws/colcon_ws/install/rmw_fastrtps_shared_cpp/lib/librmw_fastrtps_shared_cpp.so
--Type <RET> for more, q to quit, c to continue without paging--
0x00007fb6c2bce0e0  0x00007fb6c2bce2b3  No          /root/ros2_ws/colcon_ws/install/rosidl_typesupport_fastrtps_c/lib/librosidl_typesupport_fastrtps_c.so
0x00007fb6c2bc8720  0x00007fb6c2bc9486  No          /root/ros2_ws/colcon_ws/install/rosidl_typesupport_fastrtps_cpp/lib/librosidl_typesupport_fastrtps_cpp.so
0x00007fb6bb7c8ce0  0x00007fb6bb7e8a7b  No          /root/ros2_ws/colcon_ws/install/rmw_dds_common/lib/librmw_dds_common.so
0x00007fb6c2bc10a0  0x00007fb6c2bc1297  No          /root/ros2_ws/colcon_ws/install/rmw_dds_common/lib/librmw_dds_common__rosidl_typesupport_cpp.so
0x00007fb6bb748c40  0x00007fb6bb76a6bc  No          /root/ros2_ws/colcon_ws/install/rosidl_dynamic_typesupport_fastrtps/lib/librosidl_dynamic_typesupport_fastrtps.so
0x00007fb6baf53e70  0x00007fb6bb578934  No          /root/ros2_ws/colcon_ws/install/fastrtps/lib/libfastrtps.so.2.12
0x00007fb6c2bb0b40  0x00007fb6c2bb86e9  No          /root/ros2_ws/colcon_ws/install/fastcdr/lib/libfastcdr.so.1
0x00007fb6c2ba6040  0x00007fb6c2ba60f9  No          /root/ros2_ws/colcon_ws/install/rosidl_typesupport_introspection_cpp/lib/librosidl_typesupport_introspection_cpp.so
0x00007fb6c2ba1040  0x00007fb6c2ba10f9  No          /root/ros2_ws/colcon_ws/install/rosidl_typesupport_introspection_c/lib/librosidl_typesupport_introspection_c.so
0x00007fb6c2b99500  0x00007fb6c2b9b786  No          /root/ros2_ws/colcon_ws/install/rmw_dds_common/lib/librmw_dds_common__rosidl_generator_c.so
0x00007fb6c2b92600  0x00007fb6c2b93b91  No          /root/ros2_ws/colcon_ws/install/rosidl_typesupport_cpp/lib/librosidl_typesupport_cpp.so
0x00007fb6c00353c0  0x00007fb6c003e0f9  No          /lib/x86_64-linux-gnu/libtinyxml2.so.9
0x00007fb6bad04d70  0x00007fb6bad5bede  No          /lib/x86_64-linux-gnu/libssl.so.3
0x00007fb6ba955000  0x00007fb6babafe22  No          /lib/x86_64-linux-gnu/libcrypto.so.3
0x00007fb6b9f14720  0x00007fb6b9fc9298  No          /lib/x86_64-linux-gnu/libgstreamer-1.0.so.0
0x00007fb6c0004280  0x00007fb6c000d5bf  No          /lib/x86_64-linux-gnu/libunwind.so.8
0x00007fb6b9e492b0  0x00007fb6b9eadabc  No          /lib/x86_64-linux-gnu/libdw.so.1
0x00007fb6b9e1a5a0  0x00007fb6b9e2d31c  No          /lib/x86_64-linux-gnu/libelf.so.1
0x00007fb6b9e108e0  0x00007fb6b9e132b8  No          /lib/x86_64-linux-gnu/libdebuginfod.so.1
0x00007fb6b9d7cd00  0x00007fb6b9deb251  No          /lib/x86_64-linux-gnu/libcurl-gnutls.so.4
0x00007fb6b9d471c0  0x00007fb6b9d5b546  No          /lib/x86_64-linux-gnu/libnghttp2.so.14
0x00007fb6b9d233e0  0x00007fb6b9d26579  No          /lib/x86_64-linux-gnu/libidn2.so.0
0x00007fb6b9d07d80  0x00007fb6b9d16fd9  No          /lib/x86_64-linux-gnu/librtmp.so.1
0x00007fb6b9ca4460  0x00007fb6b9ce4698  No          /lib/x86_64-linux-gnu/libssh.so.4
0x00007fb6b9c833e0  0x00007fb6b9c84ea3  No          /lib/x86_64-linux-gnu/libpsl.so.5
0x00007fb6b9c45260  0x00007fb6b9c677dc  No          /lib/x86_64-linux-gnu/libnettle.so.8
0x00007fb6b9a83b40  0x00007fb6b9ba9afd  No          /lib/x86_64-linux-gnu/libgnutls.so.30
0x00007fb6b9a093f0  0x00007fb6b9a3e8c8  No          /lib/x86_64-linux-gnu/libgssapi_krb5.so.2
0x00007fb6b99ad000  0x00007fb6b99e4e0c  No          /lib/x86_64-linux-gnu/libldap-2.5.so.0
0x00007fb6b998f360  0x00007fb6b9996341  No          /lib/x86_64-linux-gnu/liblber-2.5.so.0
0x00007fb6b98c7220  0x00007fb6b9978f02  No          /lib/x86_64-linux-gnu/libzstd.so.1
0x00007fb6b98b0140  0x00007fb6b98b70da  No          /lib/x86_64-linux-gnu/libbrotlidec.so.1
--Type <RET> for more, q to quit, c to continue without paging--
0x00007fb6b9716790  0x00007fb6b974bb51  No          /lib/x86_64-linux-gnu/libunistring.so.2
0x00007fb6b96c5c80  0x00007fb6b96d7b89  No          /lib/x86_64-linux-gnu/libhogweed.so.6
0x00007fb6b9645440  0x00007fb6b96a354d  No          /lib/x86_64-linux-gnu/libgmp.so.10
0x00007fb6b9529be0  0x00007fb6b95cc3a0  No          /lib/x86_64-linux-gnu/libp11-kit.so.0
0x00007fb6b94eb4a0  0x00007fb6b94f820b  No          /lib/x86_64-linux-gnu/libtasn1.so.6
0x00007fb6b943ff50  0x00007fb6b949ab77  No          /lib/x86_64-linux-gnu/libkrb5.so.3
0x00007fb6b93f24c0  0x00007fb6b940c5f2  No          /lib/x86_64-linux-gnu/libk5crypto.so.3
0x00007fb6c2b8c3c0  0x00007fb6c2b8cf59  No          /lib/x86_64-linux-gnu/libcom_err.so.2
0x00007fb6b93e3630  0x00007fb6b93e8a24  No          /lib/x86_64-linux-gnu/libkrb5support.so.0
0x00007fb6b93c8860  0x00007fb6b93d80e4  No          /lib/x86_64-linux-gnu/libsasl2.so.2
0x00007fb6b93a3080  0x00007fb6b93a35b5  No          /lib/x86_64-linux-gnu/libbrotlicommon.so.1
0x00007fb6b939d260  0x00007fb6b939e404  No          /lib/x86_64-linux-gnu/libkeyutils.so.1
0x00007fb6b938a6a0  0x00007fb6b9393229  No          /lib/x86_64-linux-gnu/libresolv.so.2
0x00007fb6c0026b40  0x00007fb6c0029157  No          /usr/lib/python3/dist-packages/gi/overrides/_gi_gst.cpython-310-x86_64-linux-gnu.so
0x00007fb6b9182440  0x00007fb6b91831db  No          /usr/lib/python3.10/lib-dynload/_queue.cpython-310-x86_64-linux-gnu.so
mjcarroll commented 11 months ago

That only makes sense if gstreamer depends on boost, which I don't know if that is the case.

I think that it's making use of pygobject, which doesn't seem to have any boost in the build: https://gitlab.gnome.org/GNOME/pygobject

iuhilnehc-ynos commented 11 months ago

Thanks for your reply. These help me a lot.

I tried to find out the difference of gst_rclpy.py run on ROS 2 source galactic between ubunt20 and ubuntu22 by debugging the path (layout asm in gdb step by step -> libstdc++.so.6.0.[28|30] -> libgcc_s.so.1 -> libunwind.so.8.0.1(not in ubuntu20) ).

After building the libunwind-1.3.2, which is needed on ubuntu22, the gst_rclpy.py works well with the build version of libunwind.so.8.0.1. (The gst_rclpy.py also works well on ROS 2 rolling with the libunwind-1.3.2 on ubuntu22.)

Unfortunately, I have no theory to convince myself that this is a solution, it might only adjust the code mapping to update timing access for certain functions.

@jwakely, could you share some information with me? I would greatly appreciate it.

Updated: Building libunwind-1.3.2 with default options mentioned above doesn't include the --enable-cxx-exceptions. :sweat:

iuhilnehc-ynos commented 11 months ago

It seems it's the problem of mixed-using the _Unwind_RaiseException and _Unwind_Resume between gcc and libunwind.

Thread 1 "python3" hit Breakpoint 1, 0x00007ffff5f65c38 in _Unwind_RaiseException () from /lib/x86_64-linux-gnu/libgcc_s.so.1
(gdb) c
Continuing.

Thread 1 "python3" hit Breakpoint 2, _Unwind_Resume (exception_object=0x555555fdf8c0) at unwind/Resume.c:30
30  {
(gdb) c
Continuing.
detailed backtrace

```shell chenlh ros2-master $ gdb /usr/bin/python3 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 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: . Find the GDB manual and other documentation resources online at: . For help, type "help". Type "apropos word" to search for commands related to "word"... Reading symbols from /usr/bin/python3... Reading symbols from /usr/lib/debug/.build-id/8d/f1c7df42f40a5fa606666db1b65c8d9a4ddfe4.debug... (gdb) b _Unwind_RaiseException Function "_Unwind_RaiseException" not defined. Breakpoint 1 (_Unwind_RaiseException) pending. (gdb) b _Unwind_Resume Function "_Unwind_Resume" not defined. Breakpoint 2 (_Unwind_Resume) pending. (gdb) r gst_rclpy.py Starting program: /usr/bin/python3 gst_rclpy.py [Thread debugging using libthread_db enabled] Using host libthread_db library "/lib/x86_64-linux-gnu/libthread_db.so.1". warning: File "/usr/lib/x86_64-linux-gnu/debug/libstdc++.so.6.0.30-gdb.py" auto-loading has been declined by your `auto-load safe-path' set to "$debugdir:$datadir/auto-load". To enable execution of this file add add-auto-load-safe-path /usr/lib/x86_64-linux-gnu/debug/libstdc++.so.6.0.30-gdb.py line to your configuration file "/home/chenlh/.gdbinit". To completely disable this security protection add set auto-load safe-path / line to your configuration file "/home/chenlh/.gdbinit". For more information about this security protection see the "Auto-loading safe path" section in the GDB manual. E.g., run from the shell: info "(gdb)Auto-loading safe path" [New Thread 0x7ffff3b66640 (LWP 778809)] [New Thread 0x7ffff15ff640 (LWP 779085)] init [New Thread 0x7ffff0cfe640 (LWP 779130)] [New Thread 0x7ffff04fd640 (LWP 779131)] [New Thread 0x7fffefcfc640 (LWP 779132)] [New Thread 0x7fffef4fb640 (LWP 779133)] [New Thread 0x7fffeecfa640 (LWP 779134)] Thread 1 "python3" hit Breakpoint 1, 0x00007ffff5f65c38 in _Unwind_RaiseException () from /lib/x86_64-linux-gnu/libgcc_s.so.1 (gdb) bt #0 0x00007ffff5f65c38 in _Unwind_RaiseException () at /lib/x86_64-linux-gnu/libgcc_s.so.1 #1 0x00007ffff5cc69bb in __cxxabiv1::__cxa_throw(void*, std::type_info*, void (*)(void*)) (obj=, tinfo=0x7ffff2d62628 , dest=0x7ffff21c5d06 ) at ../../../../src/libstdc++-v3/libsupc++/eh_throw.cc:93 #2 0x00007ffff21e4e83 in boost::interprocess::shared_memory_object::priv_open_or_create(boost::interprocess::ipcdetail::create_enum_t, char const*, boost::interprocess::mode_t, boost::interprocess::permissions const&) (this=0x7fffffff16a0, type=boost::interprocess::ipcdetail::DoOpen, filename=0x55555600ffa0 "fastrtps_port14411", mode=boost::interprocess::read_write, perm=...) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/shared_memory_object.hpp:363 #3 0x00007ffff21e4a54 in boost::interprocess::shared_memory_object::shared_memory_object(boost::interprocess::open_only_t, char const*, boost::interprocess::mode_t) (this=0x7fffffff16a0, name=0x55555600ffa0 "fastrtps_port14411", mode=boost::interprocess::read_write) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/shared_memory_object.hpp:83 #4 0x00007ffff21f1d52 in boost::interprocess::ipcdetail::managed_open_or_create_impl::priv_open_or_create, 0ul>, boost::interprocess::iset_index, 16ul> > >(boost::interprocess::ipcdetail::create_enum_t, char const* const&, unsigned long, boost::interprocess::mode_t, void const*, boost::interprocess::permissions const&, boost::interprocess::ipcdetail::create_open_func, 0ul>, boost::interprocess::iset_index, 16ul> >) (this=0x55555600ff78, type=boost::interprocess::ipcdetail::DoOpen, id=@0x7fffffff1780: 0x55555600ffa0 "fastrtps_port14411", size=0, mode=boost::interprocess::read_write, addr=0x0, perm=..., construct_func=...) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/detail/managed_open_or_create_impl.hpp:339 #5 0x00007ffff21f0994 in boost::interprocess::ipcdetail::managed_open_or_create_impl::managed_open_or_create_impl, 0ul>, boost::interprocess::iset_index, 16ul> > >(boost::interprocess::open_only_t, char const* const&, boost::interprocess::mode_t, void const*, boost::interprocess::ipcdetail::create_open_func, 0ul>, boost::interprocess::iset_index, 16ul> > const&) (this=0x55555600ff78, id=@0x7fffffff1780: 0x55555600ffa0 "fastrtps_port14411", mode=boost::interprocess::read_write, addr=0x0, construct_func=...) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/detail/managed_open_or_create_impl.hpp:202 #6 0x00007ffff22442bd in boost::interprocess::basic_managed_shared_memory, 0ul>, boost::interprocess::iset_index>::basic_managed_shared_memory(boost::interprocess::open_only_t, char const*, void const*) (this=0x55555600ff70, name=0x55555600ffa0 "fastrtps_port14411", addr=0x0) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/managed_shared_memory.hpp:151 #7 0x00007ffff2243ec2 in eprosima::fastdds::rtps::SharedSegment, 0ul>, boost::interprocess::iset_index>, boost::interprocess::shared_memory_object>::SharedSegment(boost::interprocess::open_only_t, std::__cxx11::basic_string, std::allocator > const&) (this=0x55555600ffc0, name=...) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/utils/shared_memory/SharedMemSegment.hpp:341 #8 0x00007ffff27c0193 in eprosima::fastdds::rtps::SharedMemGlobal::open_port_internal(unsigned int, unsigned int, unsigned int, eprosima::fastdds::rtps::SharedMemGlobal::Port::OpenMode, std::shared_ptr) (this=0x555555d71b00, port_id=14411, max_buffer_descriptors=512, healthy_check_timeout_ms=1000, open_mode=eprosima::fastdds::rtps::SharedMemGlobal::Port::OpenMode::ReadExclusive, regenerating_port=...) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/transport/shared_mem/SharedMemGlobal.hpp:1078 #9 0x00007ffff27bf9b0 in eprosima::fastdds::rtps::SharedMemGlobal::open_port(unsigned int, unsigned int, unsigned int, eprosima::fastdds::rtps::SharedMemGlobal::Port::OpenMode) (this=0x555555d71b00, port_id=14411, max_buffer_descriptors=512, healthy_check_timeout_ms=1000, open_mode=eprosima::fastdds::rtps::SharedMemGlobal::Port::OpenMode::ReadExclusive) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/transport/shared_mem/SharedMemGlobal.hpp:991 #10 0x00007ffff27c3790 in eprosima::fastdds::rtps::SharedMemManager::open_port(unsigned int, unsigned int, unsigned int, eprosima::fastdds::rtps::SharedMemGlobal::Port::OpenMode) (this=0x555555d71a80, port_id=14411, max_descriptors=512, healthy_check_timeout_ms=1000, open_mode=eprosima::fastdds::rtps::SharedMemGlobal::Port::OpenMode::ReadExclusive) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/transport/shared_mem/SharedMemManager.hpp:996 #11 0x00007ffff27e4725 in eprosima::fastdds::rtps::SharedMemTransport::CreateInputChannelResource(eprosima::fastrtps::rtps::Locator_t const&, unsigned int, eprosima::fastdds::rtps::TransportReceiverInterface*) (this=0x555555e37300, locator=..., maxMsgSize=4294967295, receiver=0x555555d425e0) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/transport/shared_mem/SharedMemTransport.cpp:332 #12 0x00007ffff27e3590 in eprosima::fastdds::rtps::SharedMemTransport::OpenInputChannel(eprosima::fastrtps::rtps::Locator_t const&, eprosima::fastdds::rtps::TransportReceiverInterface*, unsigned int) (this=0x555555e37300, locator=..., receiver=0x555555d425e0, maxMsgSize=4294967295) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/transport/shared_mem/SharedMemTransport.cpp:138 #13 0x00007ffff22a44df in eprosima::fastrtps::rtps::ReceiverResource::ReceiverResource(eprosima::fastdds::rtps::TransportInterface&, eprosima::fastrtps::rtps::Locator_t const&, unsigned int) (this=0x555555d425e0, transport=..., locator=..., max_recv_buffer_size=4294967295) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/network/ReceiverResource.cpp:45 #14 0x00007ffff229d120 in eprosima::fastrtps::rtps::NetworkFactory::BuildReceiverResources(eprosima::fastrtps::rtps::Locator_t&, std::vector, std::allocator > >&, unsigned int) (this=0x555555fd67b0, local=..., returned_resources_list=..., receiver_max_message_size=4294967295) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/network/NetworkFactory.cpp:100 #15 0x00007ffff22ae30a in eprosima::fastrtps::rtps::RTPSParticipantImpl::createReceiverResources(eprosima::fastdds::rtps::LocatorList&, bool, bool) (this=0x555555fd6060, Locator_list=..., ApplyMutation=true, RegisterReceiver=false) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/participant/RTPSParticipantImpl.cpp:1700 #16 0x00007ffff22a9c1a in eprosima::fastrtps::rtps::RTPSParticipantImpl::RTPSParticipantImpl(unsigned int, eprosima::fastrtps::rtps::RTPSParticipantAttributes const&, eprosima::fastrtps::rtps::GuidPrefix_t const&, eprosima::fastrtps::rtps::GuidPrefix_t const&, eprosima::fastrtps::rtps::RTPSParticipant*, eprosima::fastrtps::rtps::RTPSParticipantListener*) (this=0x555555fd6060, domain_id=28, PParam=..., guidP=..., persistence_guid=..., par=0x555555f9e920, plisten=0x555555fd3f40) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/participant/RTPSParticipantImpl.cpp:358 #17 0x00007ffff22aa8f1 in eprosima::fastrtps::rtps::RTPSParticipantImpl::RTPSParticipantImpl(unsigned int, eprosima::fastrtps::rtps::RTPSParticipantAttributes const&, eprosima::fastrtps::rtps::GuidPrefix_t const&, eprosima::fastrtps::rtps::RTPSParticipant*, eprosima::fastrtps::rtps::RTPSParticipantListener*) (this=0x555555fd6060, domain_id=28, PParam=..., guidP=..., par=0x555555f9e920, plisten=0x555555fd3f40) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/participant/RTPSParticipantImpl.cpp:450 #18 0x00007ffff22d0d70 in eprosima::fastrtps::rtps::RTPSDomainImpl::createParticipant(unsigned int, bool, eprosima::fastrtps::rtps::RTPSParticipantAttributes const&, eprosima::fastrtps::rtps::RTPSParticipantListener*) (domain_id=28, enabled=false, attrs=..., listen=0x555555fd3f40) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/RTPSDomain.cpp:199 #19 0x00007ffff22d00ec in eprosima::fastrtps::rtps::RTPSDomain::createParticipant(unsigned int, bool, eprosima::fastrtps::rtps::RTPSParticipantAttributes const&, eprosima::fastrtps::rtps::RTPSParticipantListener*) (domain_id=28, enabled=false, attrs=..., listen=0x555555fd3f40) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/RTPSDomain.cpp:88 #20 0x00007ffff23c3909 in eprosima::fastdds::dds::DomainParticipantImpl::enable() (this=0x555555fd32d0) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/fastdds/domain/DomainParticipantImpl.cpp:277 #21 0x00007ffff27838f0 in eprosima::fastdds::statistics::dds::DomainParticipantImpl::enable() (this=0x555555fd32d0) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/statistics/fastdds/domain/DomainParticipantImpl.cpp:253 #22 0x00007ffff23ea284 in eprosima::fastdds::dds::DomainParticipant::enable() (this=0x555555f7e760) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/fastdds/domain/DomainParticipant.cpp:110 #23 0x00007ffff23b79eb in eprosima::fastdds::dds::DomainParticipantFactory::create_participant(unsigned int, eprosima::fastdds::dds::DomainParticipantQos const&, eprosima::fastdds::dds::DomainParticipantListener*, eprosima::fastdds::dds::StatusMask const&) (this=0x555555f70c60, did=28, qos=..., listen=0x555555f9d3b0, mask=...) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/fastdds/domain/DomainParticipantFactory.cpp:189 #24 0x00007ffff31e4850 in __create_participant(char const*, eprosima::fastdds::dds::DomainParticipantQos const&, bool, publishing_mode_t, rmw_dds_common::Context*, size_t) (identifier=0x7ffff332f112 "rmw_fastrtps_cpp", domainParticipantQos=..., leave_middleware_default_qos=false, publishing_mode=publishing_mode_t::SYNCHRONOUS, common_context=0x555555e84a50, domain_id=28) at /home/chenlh/Projects/ROS2/ros2-master/src/ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/participant.cpp:103 #25 0x00007ffff31e5f4e in rmw_fastrtps_shared_cpp::create_participant(char const*, unsigned long, rmw_security_options_s const*, rmw_discovery_options_s const*, char const*, rmw_dds_common::Context*) (identifier=0x7ffff332f112 "rmw_fastrtps_cpp", domain_id=28, security_options=0x555555f6edf8, discovery_options=0x555555f6ee10, enclave=0x555555f70330 "/", common_context=0x555555e84a50) at /home/chenlh/Projects/ROS2/ros2-master/src/ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/participant.cpp:372 #26 0x00007ffff32e7ed4 in init_context_impl(rmw_context_t*) (context=0x555555f6edd0) at /home/chenlh/Projects/ROS2/ros2-master/src/ros2/rmw_fastrtps/rmw_fastrtps_cpp/src/init_rmw_context_impl.cpp:76 #27 0x00007ffff32e85f5 in rmw_fastrtps_cpp::increment_context_impl_ref_count(rmw_context_s*) (context=0x555555f6edd0) at /home/chenlh/Projects/ROS2/ros2-master/src/ros2/rmw_fastrtps/rmw_fastrtps_cpp/src/init_rmw_context_impl.cpp:216 #28 0x00007ffff330dc6f in rmw_create_node(rmw_context_t*, char const*, char const*) (context=0x555555f6edd0, name=0x7fffffffb250 "gstreamer_crash", namespace_=0x7ffff5ff06d6 "/") at /home/chenlh/Projects/ROS2/ros2-master/src/ros2/rmw_fastrtps/rmw_fastrtps_cpp/src/rmw_node.cpp:66 #29 0x00007ffff65e6843 in rmw_create_node(rmw_context_t*, char const*, char const*) (v3=0x555555f6edd0, v2=0x7fffffffb250 "gstreamer_crash", v1=0x7ffff5ff06d6 "/") at /home/chenlh/Projects/ROS2/ros2-master/src/ros2/rmw_implementation/rmw_implementation/src/functions.cpp:263 #30 0x00007ffff5fd0c9d in rcl_node_init (node=0x555555f871f0, name=0x7fffffffb250 "gstreamer_crash", namespace_=0x7fffffffb228 "", context=0x555555e34b10, options=0x7fffffffaec0) at /home/chenlh/Projects/ROS2/ros2-master/src/ros2/rcl/rcl/src/rcl/node.c:258 #31 0x00007ffff67b6b16 in rclpy::Node::Node(char const*, char const*, rclpy::Context&, pybind11::object, bool, bool) (this=0x555555f86280, node_name=0x7fffffffb250 "gstreamer_crash", namespace_=0x7fffffffb228 "", context=..., pycli_args=..., use_global_arguments=true, enable_rosout=true) at /home/chenlh/Projects/ROS2/ros2-master/src/ros2/rclpy/rclpy/src/rclpy/node.cpp:466 #32 0x00007ffff67bf70f in pybind11::detail::initimpl::construct_or_initialize(char const*&&, char const*&&, rclpy::Context&, pybind11::object&&, bool&&, bool&&) () at /usr/include/pybind11/detail/init.h:61 #33 0x00007ffff67bd8e5 in pybind11::detail::initimpl::constructor::execute >, , 0>(pybind11::class_ >&)::{lambda(pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool)#1}::operator()(pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool) const (__closure=0x555555d3e258, v_h=..., args#0=0x7fffffffb250 "gstreamer_crash", args#1=0x7fffffffb228 "", args#2=..., args#3=..., args#4=true, args#5=true) at /usr/include/pybind11/detail/init.h:178 #34 0x00007ffff67cc9f7 in pybind11::detail::argument_loader::call_impl::execute >, , 0>(pybind11::class_ >&)::{lambda(pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool)#1}&, 0ul, 1ul, 2ul, 3ul, 4ul, 5ul, 6ul, pybind11::detail::void_type>(pybind11::detail::initimpl::constructor::execute >, , 0>(pybind11::class_ >&)::{lambda(pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool)#1}&, std::integer_sequence, pybind11::detail::void_type&&) && (this=0x7fffffffb1f0, f=...) at /usr/include/pybind11/cast.h:1207 #35 0x00007ffff67c9e74 in pybind11::detail::argument_loader::call::execute >, , 0>(pybind11::class_ >&)::{lambda(pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool)#1}&>(pybind11::detail::initimpl::constructor::execute >, , 0>(pybind11::class_ >&)::{lambda(pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool)#1}&) && (this=0x7fffffffb1f0, f=...) at /usr/include/pybind11/cast.h:1184 #36 0x00007ffff67c6caf in pybind11::cpp_function::initialize::execute >, , 0>(pybind11::class_ >&)::{lambda(pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool)#1}, void, pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool, pybind11::name, pybind11::is_method, pybind11::sibling, pybind11::detail::is_new_style_constructor>(pybind11::class_ >&&, void (*)(pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool), pybind11::name const&, pybind11::is_method const&, pybind11::sibling const&, pybind11::detail::is_new_style_constructor const&)::{lambda(pybind11::detail::function_call&)#3}::operator()(pybind11::detail::function_call&) const (__closure=0x0, call=...) at /usr/include/pybind11/pybind11.h:233 #37 0x00007ffff67c7078 in pybind11::cpp_function::initialize::execute >, , 0>(pybind11::class_ >&)::{lambda(pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool)#1}, void, pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool, pybind11::name, pybind11::is_method, pybind11::sibling, pybind11::detail::is_new_style_constructor>(pybind11::class_ >&&, void (*)(pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool), pybind11::name const&, pybind11::is_method const&, pybind11::sibling const&, pybind11::detail::is_new_style_constructor const&)::{lambda(pybind11::detail::function_call&)#3}::_FUN(pybind11::detail::function_call&) () at /usr/include/pybind11/pybind11.h:210 #38 0x00007ffff66db9e0 in pybind11::cpp_function::dispatcher(_object*, _object*, _object*) (self=, args_in=(, 'gstreamer_crash', '', , None, True, True), kwargs_in=0x0) at /usr/include/pybind11/pybind11.h:835 #39 0x00005555556b3e0e in cfunction_call (func=, args=, kwargs=) at ../Objects/methodobject.c:543 #40 0x00005555556aa5eb in _PyObject_MakeTpCall (tstate=0x555555b66bf0, callable=, args=, nargs=, keywords=0x0) at ../Objects/call.c:215 #41 0x00005555556c2910 in _PyObject_VectorcallTstate (kwnames=, nargsf=, args=0x7ffff0dd31f0, callable=, tstate=0x555555b66bf0) at ../Include/cpython/abstract.h:112 #42 _PyObject_VectorcallTstate (kwnames=, nargsf=, args=0x7ffff0dd31f0, callable=, tstate=0x555555b66bf0) at ../Include/cpython/abstract.h:99 #43 method_vectorcall (method=, args=, nargsf=, kwnames=) at ../Objects/classobject.c:83 #44 0x00005555556bed67 in slot_tp_init (self=self@entry=, args=args@entry=('gstreamer_crash', '', , None, True, True), kwds=kwds@entry=0x0) at ../Objects/typeobject.c:7737 #45 0x00005555556aa98b in type_call (type=, args=('gstreamer_crash', '', , None, True, True), kwds=0x0) at ../Objects/typeobject.c:1135 #46 0x00007ffff66d5c51 in pybind11::detail::pybind11_meta_call(PyObject*, PyObject*, PyObject*) (type=, __doc__=None, __module__='rclpy._rclpy_pybind11', pointer=, get_fully_qualified_name=, logger_name=, get_node_name=, get_namespace=, get_count_publishers=, get_count_subscribers=, get_node_names_and_namespaces=, get_node_names_and_namespaces_with_enclaves=, get_action_client_names_and_types_by_node=, get_action_server_names_and_types_by_node=, get_action_names_and_types=, get_parameters=) at remote 0x555555d3e320>, args=('gstreamer_crash', '', , None, True, True), kwargs=0x0) at /usr/include/pybind11/detail/class.h:174 #47 0x00005555556aa5eb in _PyObject_MakeTpCall (tstate=0x555555b66bf0, callable=, __doc__=None, __module__='rclpy._rclpy_pybind11', pointer=, get_fully_qualified_name=, logger_name=, get_node_name=, get_namespace=, get_count_publishers=, get_count_subscribers=, get_node_names_and_namespaces=, get_node_names_and_namespaces_with_enclaves=, get_action_client_names_and_types_by_node=, get_action_server_names_and_types_by_node=, get_action_names_and_types=, get_parameters=) at remote 0x555555d3e320>, args=, nargs=, keywords=0x0) at ../Objects/call.c:215 #48 0x00005555556a31f1 in _PyObject_VectorcallTstate (kwnames=0x0, nargsf=, args=, callable=, __doc__=None, __module__='rclpy._rclpy_pybind11', pointer=, get_fully_qualified_name=, logger_name=, get_node_name=, get_namespace=, get_count_publishers=, get_count_subscribers=, get_node_names_and_namespaces=, get_node_names_and_namespaces_with_enclaves=, get_action_client_names_and_types_by_node=, get_action_server_names_and_types_by_node=, get_action_names_and_types=, get_parameters=) at remote 0x555555d3e320>, tstate=) at ../Include/cpython/abstract.h:112 #49 _PyObject_VectorcallTstate (kwnames=0x0, nargsf=, args=0x555555e801e8, callable=, __doc__=None, __module__='rclpy._rclpy_pybind11', pointer=, get_fully_qualified_name=, logger_name=, get_node_name=, get_namespace=, get_count_publishers=, get_count_subscribers=, get_node_names_and_namespaces=, get_node_names_and_namespaces_with_enclaves=, get_action_client_names_and_types_by_node=, get_action_server_names_and_types_by_node=, get_action_names_and_types=, get_parameters=) at remote 0x555555d3e320>, tstate=) at ../Include/cpython/abstract.h:99 #50 PyObject_Vectorcall (kwnames=0x0, nargsf=, args=0x555555e801e8, callable=, __doc__=None, __module__='rclpy._rclpy_pybind11', pointer=, get_fully_qualified_name=, logger_name=, get_node_name=, get_namespace=, get_count_publishers=, get_count_subscribers=, get_node_names_and_namespaces=, get_node_names_and_namespaces_with_enclaves=, get_action_client_names_and_types_by_node=, get_action_server_names_and_types_by_node=, get_action_names_and_types=, get_parameters=) at remote 0x555555d3e320>) at ../Include/cpython/abstract.h:123 #51 call_function (kwnames=0x0, oparg=, pp_stack=, trace_info=0x7fffffffbae0, tstate=) at ../Python/ceval.c:5893 #52 _PyEval_EvalFrameDefault (tstate=, f=, throwflag=) at ../Python/ceval.c:4181 #53 0x00005555556b470c in _PyEval_EvalFrame (throwflag=0, f=Frame 0x555555e80010, for file /home/chenlh/Projects/ROS2/ros2-master/install/lib/python3.10/site-packages/rclpy/node.py, line 185, in __init__ (self=, _callbacks=[], _logging_initialized=True, _Context__context=) at remote 0x7ffff6fcff10>, _parameters={}, _publishers=[], _subscriptions=[], _clients=[], _services=[], _timers=[], _guards=[], _Node__waitables=[], _default_callback_group=) at remote 0x7ffff6ba2dd0>, _pre_set_parameters_callbacks=[], _on_set_parameters_callbacks=[], _post_set_parameters_callbacks=[], _rate_group=, _allow_undeclared_parameters=False, _parameter_overrides={}, _descriptors={}) at remote 0x7ffff6d27940>, node_name='gstreamer_crash', context=None, cli_args=None, name...(truncated), tstate=0x555555b66bf0) at ../Include/internal/pycore_ceval.h:46 #54 _PyEval_Vector (kwnames=, argcount=, args=, locals=0x0, con=0x7ffff0db2840, tstate=0x555555b66bf0) at ../Python/ceval.c:5067 #55 _PyFunction_Vectorcall (func=, stack=, nargsf=, kwnames=) at ../Objects/call.c:342 #56 0x00005555556a982d in _PyObject_FastCallDictTstate (tstate=0x555555b66bf0, callable=, args=, nargsf=, kwargs=) at ../Objects/call.c:153 #57 0x00005555556be744 in _PyObject_Call_Prepend (kwargs={'context': None, 'cli_args': None, 'namespace': None, 'use_global_arguments': True, 'enable_rosout': True, 'start_parameter_services': True, 'parameter_overrides': None, 'allow_undeclared_parameters': False, 'automatically_declare_parameters_from_overrides': False, 'enable_logger_service': False}, args=('gstreamer_crash',), obj=, _callbacks=[], _logging_initialized=True, _Context__context=) at remote 0x7ffff6fcff10>, _parameters={}, _publishers=[], _subscriptions=[], _clients=[], _services=[], _timers=[], _guards=[], _Node__waitables=[], _default_callback_group=) at remote 0x7ffff6ba2dd0>, _pre_set_parameters_callbacks=[], _on_set_parameters_callbacks=[], _post_set_parameters_callbacks=[], _rate_group=, _allow_undeclared_parameters=False, _parameter_overrides={}, _descriptors={}) at remote 0x7ffff6d27940>, callable=, tstate=0x555555b66bf0) at ../Objects/call.c:431 #58 slot_tp_init (self=self@entry=, _callbacks=[], _logging_initialized=True, _Context__context=) at remote 0x7ffff6fcff10>, _parameters={}, _publishers=[], _subscriptions=[], _clients=[], _services=[], _timers=[], _guards=[], _Node__waitables=[], _default_callback_group=) at remote 0x7ffff6ba2dd0>, _pre_set_parameters_callbacks=[], _on_set_parameters_callbacks=[], _post_set_parameters_callbacks=[], _rate_group=, _allow_undeclared_parameters=False, _parameter_overrides={}, _descriptors={}) at remote 0x7ffff6d27940>, args=args@entry=('gstreamer_crash',), kwds=kwds@entry={'context': None, 'cli_args': None, 'namespace': None, 'use_global_arguments': True, 'enable_rosout': True, 'start_parameter_services': True, 'parameter_overrides': None, 'allow_undeclared_parameters': False, 'automatically_declare_parameters_from_overrides': False, 'enable_logger_service': False}) at ../Objects/typeobject.c:7734 #59 0x00005555556aa58c in type_call (kwds={'context': None, 'cli_args': None, 'namespace': None, 'use_global_arguments': True, 'enable_rosout': True, 'start_parameter_services': True, 'parameter_overrides': None, 'allow_undeclared_parameters': False, 'automatically_declare_parameters_from_overrides': False, 'enable_logger_service': False}, args=('gstreamer_crash',), type=) at ../Objects/typeobject.c:1135 #60 _PyObject_MakeTpCall (tstate=0x555555b66bf0, callable=, args=, nargs=, keywords=('context', 'cli_args', 'namespace', 'use_global_arguments', 'enable_rosout', 'start_parameter_services', 'parameter_overrides', 'allow_undeclared_parameters', 'automatically_declare_parameters_from_overrides', 'enable_logger_service')) at ../Objects/call.c:215 #61 0x00005555556a3908 in _PyObject_VectorcallTstate (kwnames=('context', 'cli_args', 'namespace', 'use_global_arguments', 'enable_rosout', 'start_parameter_services', 'parameter_overrides', 'allow_undeclared_parameters', 'automatically_declare_parameters_from_overrides', 'enable_logger_service'), nargsf=, args=, callable=, tstate=0x555555b66bf0) at ../Include/cpython/abstract.h:112 #62 _PyObject_VectorcallTstate (kwnames=('context', 'cli_args', 'namespace', 'use_global_arguments', 'enable_rosout', 'start_parameter_services', 'parameter_overrides', 'allow_undeclared_parameters', 'automatically_declare_parameters_from_overrides', 'enable_logger_service'), nargsf=, args=, callable=, tstate=0x555555b66bf0) at ../Include/cpython/abstract.h:99 #63 PyObject_Vectorcall (kwnames=('context', 'cli_args', 'namespace', 'use_global_arguments', 'enable_rosout', 'start_parameter_services', 'parameter_overrides', 'allow_undeclared_parameters', 'automatically_declare_parameters_from_overrides', 'enable_logger_service'), nargsf=, args=, callable=) at ../Include/cpython/abstract.h:123 #64 call_function (kwnames=('context', 'cli_args', 'namespace', 'use_global_arguments', 'enable_rosout', 'start_parameter_services', 'parameter_overrides', 'allow_undeclared_parameters', 'automatically_declare_parameters_from_overrides', 'enable_logger_service'), oparg=, pp_stack=, trace_info=0x7fffffffbe30, tstate=) at ../Python/ceval.c:5893 #65 _PyEval_EvalFrameDefault (tstate=, f=, throwflag=) at ../Python/ceval.c:4231 #66 0x00005555556b470c in _PyEval_EvalFrame (throwflag=0, f=Frame 0x555555eb1920, for file /home/chenlh/Projects/ROS2/ros2-master/install/lib/python3.10/site-packages/rclpy/__init__.py, line 180, in create_node (node_name='gstreamer_crash', context=None, cli_args=None, namespace=None, use_global_arguments=True, enable_rosout=True, start_parameter_services=True, parameter_overrides=None, allow_undeclared_parameters=False, automatically_declare_parameters_from_overrides=False, enable_logger_service=False, Node=), tstate=0x555555b66bf0) at ../Include/internal/pycore_ceval.h:46 #67 _PyEval_Vector (kwnames=, argcount=, args=, locals=0x0, con=0x7ffff6a1e690, tstate=0x555555b66bf0) at ../Python/ceval.c:5067 #68 _PyFunction_Vectorcall (func=, stack=, nargsf=, kwnames=) at ../Objects/call.c:342 #69 0x00005555556a28a2 in _PyObject_VectorcallTstate (kwnames=0x0, nargsf=, args=0x7ffff6e3f9b0, callable=, tstate=0x555555b66bf0) at ../Include/cpython/abstract.h:114 #70 PyObject_Vectorcall (kwnames=0x0, nargsf=, args=0x7ffff6e3f9b0, callable=) at ../Include/cpython/abstract.h:123 #71 call_function (kwnames=0x0, oparg=, pp_stack=, trace_info=0x7fffffffc010, tstate=) at ../Python/ceval.c:5893 #72 _PyEval_EvalFrameDefault (tstate=, f=, throwflag=) at ../Python/ceval.c:4181 #73 0x000055555578de56 in _PyEval_EvalFrame (throwflag=0, f=Frame 0x7ffff6e3f840, for file /home/chenlh/Projects/ROS2/ros2-master/gst_rclpy.py, line 30, in (), tstate=0x555555b66bf0) at ../Include/internal/pycore_ceval.h:46 #74 _PyEval_Vector (tstate=0x555555b66bf0, con=, locals=, args=, argcount=, kwnames=) at ../Python/ceval.c:5067 #75 0x000055555578dcf6 in PyEval_EvalCode (co=, globals={'__name__': '__main__', '__doc__': None, '__package__': None, '__loader__': , '__spec__': None, '__annotations__': {}, '__builtins__': , '__file__': '/home/chenlh/Projects/ROS2/ros2-master/gst_rclpy.py', '__cached__': None, 'sys': , 'time': , 'rclpy': , 'gi': , 'Gst': , __spec__=, origin=None, loader_state=None, submodule_search_locations=None, _set_fileattr=False, _cached=None) at remote 0x7ffff6a63eb0>, _introspection_module=) at ../Python/ceval.c:1134 #76 0x00005555557b87d8 in run_eval_code_obj (tstate=0x555555b66bf0, co=0x7ffff6ef5dc0, globals={'__name__': '__main__', '__doc__': None, '__package__': None, '__loader__': , '__spec__': None, '__annotations__': {}, '__builtins__': , '__file__': '/home/chenlh/Projects/ROS2/ros2-master/gst_rclpy.py', '__cached__': None, 'sys': , 'time': , 'rclpy': , 'gi': , 'Gst': , __spec__=, origin=None, loader_state=None, submodule_search_locations=None, _set_fileattr=False, _cached=None) at remote 0x7ffff6a63eb0>, _introspection_module=, '__spec__': None, '__annotations__': {}, '__builtins__': , '__file__': '/home/chenlh/Projects/ROS2/ros2-master/gst_rclpy.py', '__cached__': None, 'sys': , 'time': , 'rclpy': , 'gi': , 'Gst': , __spec__=, origin=None, loader_state=None, submodule_search_locations=None, _set_fileattr=False, _cached=None) at remote 0x7ffff6a63eb0>, _introspection_module=, filename=, globals={'__name__': '__main__', '__doc__': None, '__package__': None, '__loader__': , '__spec__': None, '__annotations__': {}, '__builtins__': , '__file__': '/home/chenlh/Projects/ROS2/ros2-master/gst_rclpy.py', '__cached__': None, 'sys': , 'time': , 'rclpy': , 'gi': , 'Gst': , __spec__=, origin=None, loader_state=None, submodule_search_locations=None, _set_fileattr=False, _cached=None) at remote 0x7ffff6a63eb0>, _introspection_module=, '__spec__': None, '__annotations__': {}, '__builtins__': , '__file__': '/home/chenlh/Projects/ROS2/ros2-master/gst_rclpy.py', '__cached__': None, 'sys': , 'time': , 'rclpy': , 'gi': , 'Gst': , __spec__=, origin=None, loader_state=None, submodule_search_locations=None, _set_fileattr=False, _cached=None) at remote 0x7ffff6a63eb0>, _introspection_module=, arena=) at ../Python/pythonrun.c:1312 #78 0x00005555557b8525 in pyrun_file (fp=fp@entry=0x555555b44f20, filename=filename@entry='/home/chenlh/Projects/ROS2/ros2-master/gst_rclpy.py', start=start@entry=257, globals=globals@entry={'__name__': '__main__', '__doc__': None, '__package__': None, '__loader__': , '__spec__': None, '__annotations__': {}, '__builtins__': , '__file__': '/home/chenlh/Projects/ROS2/ros2-master/gst_rclpy.py', '__cached__': None, 'sys': , 'time': , 'rclpy': , 'gi': , 'Gst': , __spec__=, origin=None, loader_state=None, submodule_search_locations=None, _set_fileattr=False, _cached=None) at remote 0x7ffff6a63eb0>, _introspection_module=, '__spec__': None, '__annotations__': {}, '__builtins__': , '__file__': '/home/chenlh/Projects/ROS2/ros2-master/gst_rclpy.py', '__cached__': None, 'sys': , 'time': , 'rclpy': , 'gi': , 'Gst': , __spec__=, origin=None, loader_state=None, submodule_search_locations=None, _set_fileattr=False, _cached=None) at remote 0x7ffff6a63eb0>, _introspection_module=, argv=) at ../Modules/main.c:720 #86 0x00007ffff7c29d90 in __libc_start_call_main (main=main@entry=0x555555780c70

, argc=argc@entry=2, argv=argv@entry=0x7fffffffc4c8) at ../sysdeps/nptl/libc_start_call_main.h:58 #87 0x00007ffff7c29e40 in __libc_start_main_impl (main=0x555555780c70
, argc=2, argv=0x7fffffffc4c8, init=, fini=, rtld_fini=, stack_end=0x7fffffffc4b8) at ../csu/libc-start.c:392 #88 0x0000555555780ba5 in _start () (gdb) c Continuing. Thread 1 "python3" hit Breakpoint 2, _Unwind_Resume (exception_object=0x555556010080) at unwind/Resume.c:30 30 { (gdb) bt #0 _Unwind_Resume (exception_object=0x555556010080) at unwind/Resume.c:30 #1 0x00007ffff21e4a78 in boost::interprocess::shared_memory_object::shared_memory_object(boost::interprocess::open_only_t, char const*, boost::interprocess::mode_t) (this=0x7fffffff16a0, name=0x55555600ffa0 "fastrtps_port14411", mode=boost::interprocess::read_write) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/shared_memory_object.hpp:83 #2 0x00007ffff21f1d52 in boost::interprocess::ipcdetail::managed_open_or_create_impl::priv_open_or_create, 0ul>, boost::interprocess::iset_index, 16ul> > >(boost::interprocess::ipcdetail::create_enum_t, char const* const&, unsigned long, boost::interprocess::mode_t, void const*, boost::interprocess::permissions const&, boost::interprocess::ipcdetail::create_open_func, 0ul>, boost::interprocess::iset_index, 16ul> >) (this=0x55555600ff78, type=boost::interprocess::ipcdetail::DoOpen, id=@0x7fffffff1780: 0x55555600ffa0 "fastrtps_port14411", size=0, mode=boost::interprocess::read_write, addr=0x0, perm=..., construct_func=...) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/detail/managed_open_or_create_impl.hpp:339 #3 0x00007ffff21f0994 in boost::interprocess::ipcdetail::managed_open_or_create_impl::managed_open_or_create_impl, 0ul>, boost::interprocess::iset_index, 16ul> > >(boost::interprocess::open_only_t, char const* const&, boost::interprocess::mode_t, void const*, boost::interprocess::ipcdetail::create_open_func, 0ul>, boost::interprocess::iset_index, 16ul> > const&) (this=0x55555600ff78, id=@0x7fffffff1780: 0x55555600ffa0 "fastrtps_port14411", mode=boost::interprocess::read_write, addr=0x0, construct_func=...) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/detail/managed_open_or_create_impl.hpp:202 #4 0x00007ffff22442bd in boost::interprocess::basic_managed_shared_memory, 0ul>, boost::interprocess::iset_index>::basic_managed_shared_memory(boost::interprocess::open_only_t, char const*, void const*) (this=0x55555600ff70, name=0x55555600ffa0 "fastrtps_port14411", addr=0x0) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/thirdparty/boost/include/boost/interprocess/managed_shared_memory.hpp:151 #5 0x00007ffff2243ec2 in eprosima::fastdds::rtps::SharedSegment, 0ul>, boost::interprocess::iset_index>, boost::interprocess::shared_memory_object>::SharedSegment(boost::interprocess::open_only_t, std::__cxx11::basic_string, std::allocator > const&) (this=0x55555600ffc0, name=...) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/utils/shared_memory/SharedMemSegment.hpp:341 #6 0x00007ffff27c0193 in eprosima::fastdds::rtps::SharedMemGlobal::open_port_internal(unsigned int, unsigned int, unsigned int, eprosima::fastdds::rtps::SharedMemGlobal::Port::OpenMode, std::shared_ptr) (this=0x555555d71b00, port_id=14411, max_buffer_descriptors=512, healthy_check_timeout_ms=1000, open_mode=eprosima::fastdds::rtps::SharedMemGlobal::Port::OpenMode::ReadExclusive, regenerating_port=...) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/transport/shared_mem/SharedMemGlobal.hpp:1078 #7 0x00007ffff27bf9b0 in eprosima::fastdds::rtps::SharedMemGlobal::open_port(unsigned int, unsigned int, unsigned int, eprosima::fastdds::rtps::SharedMemGlobal::Port::OpenMode) (this=0x555555d71b00, port_id=14411, max_buffer_descriptors=512, healthy_check_timeout_ms=1000, open_mode=eprosima::fastdds::rtps::SharedMemGlobal::Port::OpenMode::ReadExclusive) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/transport/shared_mem/SharedMemGlobal.hpp:991 #8 0x00007ffff27c3790 in eprosima::fastdds::rtps::SharedMemManager::open_port(unsigned int, unsigned int, unsigned int, eprosima::fastdds::rtps::SharedMemGlobal::Port::OpenMode) (this=0x555555d71a80, port_id=14411, max_descriptors=512, healthy_check_timeout_ms=1000, open_mode=eprosima::fastdds::rtps::SharedMemGlobal::Port::OpenMode::ReadExclusive) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/transport/shared_mem/SharedMemManager.hpp:996 #9 0x00007ffff27e4725 in eprosima::fastdds::rtps::SharedMemTransport::CreateInputChannelResource(eprosima::fastrtps::rtps::Locator_t const&, unsigned int, eprosima::fastdds::rtps::TransportReceiverInterface*) (this=0x555555e37300, locator=..., maxMsgSize=4294967295, receiver=0x555555d425e0) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/transport/shared_mem/SharedMemTransport.cpp:332 #10 0x00007ffff27e3590 in eprosima::fastdds::rtps::SharedMemTransport::OpenInputChannel(eprosima::fastrtps::rtps::Locator_t const&, eprosima::fastdds::rtps::TransportReceiverInterface*, unsigned int) (this=0x555555e37300, locator=..., receiver=0x555555d425e0, maxMsgSize=4294967295) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/transport/shared_mem/SharedMemTransport.cpp:138 #11 0x00007ffff22a44df in eprosima::fastrtps::rtps::ReceiverResource::ReceiverResource(eprosima::fastdds::rtps::TransportInterface&, eprosima::fastrtps::rtps::Locator_t const&, unsigned int) (this=0x555555d425e0, transport=..., locator=..., max_recv_buffer_size=4294967295) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/network/ReceiverResource.cpp:45 #12 0x00007ffff229d120 in eprosima::fastrtps::rtps::NetworkFactory::BuildReceiverResources(eprosima::fastrtps::rtps::Locator_t&, std::vector, std::allocator > >&, unsigned int) (this=0x555555fd67b0, local=..., returned_resources_list=..., receiver_max_message_size=4294967295) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/network/NetworkFactory.cpp:100 #13 0x00007ffff22ae30a in eprosima::fastrtps::rtps::RTPSParticipantImpl::createReceiverResources(eprosima::fastdds::rtps::LocatorList&, bool, bool) (this=0x555555fd6060, Locator_list=..., ApplyMutation=true, RegisterReceiver=false) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/participant/RTPSParticipantImpl.cpp:1700 #14 0x00007ffff22a9c1a in eprosima::fastrtps::rtps::RTPSParticipantImpl::RTPSParticipantImpl(unsigned int, eprosima::fastrtps::rtps::RTPSParticipantAttributes const&, eprosima::fastrtps::rtps::GuidPrefix_t const&, eprosima::fastrtps::rtps::GuidPrefix_t const&, eprosima::fastrtps::rtps::RTPSParticipant*, eprosima::fastrtps::rtps::RTPSParticipantListener*) (this=0x555555fd6060, domain_id=28, PParam=..., guidP=..., persistence_guid=..., par=0x555555f9e920, plisten=0x555555fd3f40) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/participant/RTPSParticipantImpl.cpp:358 #15 0x00007ffff22aa8f1 in eprosima::fastrtps::rtps::RTPSParticipantImpl::RTPSParticipantImpl(unsigned int, eprosima::fastrtps::rtps::RTPSParticipantAttributes const&, eprosima::fastrtps::rtps::GuidPrefix_t const&, eprosima::fastrtps::rtps::RTPSParticipant*, eprosima::fastrtps::rtps::RTPSParticipantListener*) (this=0x555555fd6060, domain_id=28, PParam=..., guidP=..., par=0x555555f9e920, plisten=0x555555fd3f40) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/participant/RTPSParticipantImpl.cpp:450 #16 0x00007ffff22d0d70 in eprosima::fastrtps::rtps::RTPSDomainImpl::createParticipant(unsigned int, bool, eprosima::fastrtps::rtps::RTPSParticipantAttributes const&, eprosima::fastrtps::rtps::RTPSParticipantListener*) (domain_id=28, enabled=false, attrs=..., listen=0x555555fd3f40) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/RTPSDomain.cpp:199 #17 0x00007ffff22d00ec in eprosima::fastrtps::rtps::RTPSDomain::createParticipant(unsigned int, bool, eprosima::fastrtps::rtps::RTPSParticipantAttributes const&, eprosima::fastrtps::rtps::RTPSParticipantListener*) (domain_id=28, enabled=false, attrs=..., listen=0x555555fd3f40) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/rtps/RTPSDomain.cpp:88 #18 0x00007ffff23c3909 in eprosima::fastdds::dds::DomainParticipantImpl::enable() (this=0x555555fd32d0) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/fastdds/domain/DomainParticipantImpl.cpp:277 #19 0x00007ffff27838f0 in eprosima::fastdds::statistics::dds::DomainParticipantImpl::enable() (this=0x555555fd32d0) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/statistics/fastdds/domain/DomainParticipantImpl.cpp:253 #20 0x00007ffff23ea284 in eprosima::fastdds::dds::DomainParticipant::enable() (this=0x555555f7e760) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/fastdds/domain/DomainParticipant.cpp:110 #21 0x00007ffff23b79eb in eprosima::fastdds::dds::DomainParticipantFactory::create_participant(unsigned int, eprosima::fastdds::dds::DomainParticipantQos const&, eprosima::fastdds::dds::DomainParticipantListener*, eprosima::fastdds::dds::StatusMask const&) (this=0x555555f70c60, did=28, qos=..., listen=0x555555f9d3b0, mask=...) at /home/chenlh/Projects/ROS2/ros2-master/src/eProsima/Fast-DDS/src/cpp/fastdds/domain/DomainParticipantFactory.cpp:189 #22 0x00007ffff31e4850 in __create_participant(char const*, eprosima::fastdds::dds::DomainParticipantQos const&, bool, publishing_mode_t, rmw_dds_common::Context*, size_t) (identifier=0x7ffff332f112 "rmw_fastrtps_cpp", domainParticipantQos=..., leave_middleware_default_qos=false, publishing_mode=publishing_mode_t::SYNCHRONOUS, common_context=0x555555e84a50, domain_id=28) at /home/chenlh/Projects/ROS2/ros2-master/src/ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/participant.cpp:103 #23 0x00007ffff31e5f4e in rmw_fastrtps_shared_cpp::create_participant(char const*, unsigned long, rmw_security_options_s const*, rmw_discovery_options_s const*, char const*, rmw_dds_common::Context*) (identifier=0x7ffff332f112 "rmw_fastrtps_cpp", domain_id=28, security_options=0x555555f6edf8, discovery_options=0x555555f6ee10, enclave=0x555555f70330 "/", common_context=0x555555e84a50) at /home/chenlh/Projects/ROS2/ros2-master/src/ros2/rmw_fastrtps/rmw_fastrtps_shared_cpp/src/participant.cpp:372 #24 0x00007ffff32e7ed4 in init_context_impl(rmw_context_t*) (context=0x555555f6edd0) at /home/chenlh/Projects/ROS2/ros2-master/src/ros2/rmw_fastrtps/rmw_fastrtps_cpp/src/init_rmw_context_impl.cpp:76 #25 0x00007ffff32e85f5 in rmw_fastrtps_cpp::increment_context_impl_ref_count(rmw_context_s*) (context=0x555555f6edd0) at /home/chenlh/Projects/ROS2/ros2-master/src/ros2/rmw_fastrtps/rmw_fastrtps_cpp/src/init_rmw_context_impl.cpp:216 #26 0x00007ffff330dc6f in rmw_create_node(rmw_context_t*, char const*, char const*) (context=0x555555f6edd0, name=0x7fffffffb250 "gstreamer_crash", namespace_=0x7ffff5ff06d6 "/") at /home/chenlh/Projects/ROS2/ros2-master/src/ros2/rmw_fastrtps/rmw_fastrtps_cpp/src/rmw_node.cpp:66 #27 0x00007ffff65e6843 in rmw_create_node(rmw_context_t*, char const*, char const*) (v3=0x555555f6edd0, v2=0x7fffffffb250 "gstreamer_crash", v1=0x7ffff5ff06d6 "/") at /home/chenlh/Projects/ROS2/ros2-master/src/ros2/rmw_implementation/rmw_implementation/src/functions.cpp:263 #28 0x00007ffff5fd0c9d in rcl_node_init (node=0x555555f871f0, name=0x7fffffffb250 "gstreamer_crash", namespace_=0x7fffffffb228 "", context=0x555555e34b10, options=0x7fffffffaec0) at /home/chenlh/Projects/ROS2/ros2-master/src/ros2/rcl/rcl/src/rcl/node.c:258 #29 0x00007ffff67b6b16 in rclpy::Node::Node(char const*, char const*, rclpy::Context&, pybind11::object, bool, bool) (this=0x555555f86280, node_name=0x7fffffffb250 "gstreamer_crash", namespace_=0x7fffffffb228 "", context=..., pycli_args=..., use_global_arguments=true, enable_rosout=true) at /home/chenlh/Projects/ROS2/ros2-master/src/ros2/rclpy/rclpy/src/rclpy/node.cpp:466 #30 0x00007ffff67bf70f in pybind11::detail::initimpl::construct_or_initialize(char const*&&, char const*&&, rclpy::Context&, pybind11::object&&, bool&&, bool&&) () at /usr/include/pybind11/detail/init.h:61 #31 0x00007ffff67bd8e5 in pybind11::detail::initimpl::constructor::execute >, , 0>(pybind11::class_ >&)::{lambda(pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool)#1}::operator()(pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool) const (__closure=0x555555d3e258, v_h=..., args#0=0x7fffffffb250 "gstreamer_crash", args#1=0x7fffffffb228 "", args#2=..., args#3=..., args#4=true, args#5=true) at /usr/include/pybind11/detail/init.h:178 #32 0x00007ffff67cc9f7 in pybind11::detail::argument_loader::call_impl::execute >, , 0>(pybind11::class_ >&)::{lambda(pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool)#1}&, 0ul, 1ul, 2ul, 3ul, 4ul, 5ul, 6ul, pybind11::detail::void_type>(pybind11::detail::initimpl::constructor::execute >, , 0>(pybind11::class_ >&)::{lambda(pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool)#1}&, std::integer_sequence, pybind11::detail::void_type&&) && (this=0x7fffffffb1f0, f=...) at /usr/include/pybind11/cast.h:1207 #33 0x00007ffff67c9e74 in pybind11::detail::argument_loader::call::execute >, , 0>(pybind11::class_ >&)::{lambda(pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool)#1}&>(pybind11::detail::initimpl::constructor::execute >, , 0>(pybind11::class_ >&)::{lambda(pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool)#1}&) && (this=0x7fffffffb1f0, f=...) at /usr/include/pybind11/cast.h:1184 #34 0x00007ffff67c6caf in pybind11::cpp_function::initialize::execute >, , 0>(pybind11::class_ >&)::{lambda(pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool)#1}, void, pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool, pybind11::name, pybind11::is_method, pybind11::sibling, pybind11::detail::is_new_style_constructor>(pybind11::class_ >&&, void (*)(pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool), pybind11::name const&, pybind11::is_method const&, pybind11::sibling const&, pybind11::detail::is_new_style_constructor const&)::{lambda(pybind11::detail::function_call&)#3}::operator()(pybind11::detail::function_call&) const (__closure=0x0, call=...) at /usr/include/pybind11/pybind11.h:233 #35 0x00007ffff67c7078 in pybind11::cpp_function::initialize::execute >, , 0>(pybind11::class_ >&)::{lambda(pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool)#1}, void, pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool, pybind11::name, pybind11::is_method, pybind11::sibling, pybind11::detail::is_new_style_constructor>(pybind11::class_ >&&, void (*)(pybind11::detail::value_and_holder&, char const*, char const*, rclpy::Context&, pybind11::object, bool, bool), pybind11::name const&, pybind11::is_method const&, pybind11::sibling const&, pybind11::detail::is_new_style_constructor const&)::{lambda(pybind11::detail::function_call&)#3}::_FUN(pybind11::detail::function_call&) () at /usr/include/pybind11/pybind11.h:210 #36 0x00007ffff66db9e0 in pybind11::cpp_function::dispatcher(_object*, _object*, _object*) (self=, args_in=(, 'gstreamer_crash', '', , None, True, True), kwargs_in=0x0) at /usr/include/pybind11/pybind11.h:835 #37 0x00005555556b3e0e in cfunction_call (func=, args=, kwargs=) at ../Objects/methodobject.c:543 #38 0x00005555556aa5eb in _PyObject_MakeTpCall (tstate=0x555555b66bf0, callable=, args=, nargs=, keywords=0x0) at ../Objects/call.c:215 #39 0x00005555556c2910 in _PyObject_VectorcallTstate (kwnames=, nargsf=, args=0x7ffff0dd31f0, callable=, tstate=0x555555b66bf0) at ../Include/cpython/abstract.h:112 #40 _PyObject_VectorcallTstate (kwnames=, nargsf=, args=0x7ffff0dd31f0, callable=, tstate=0x555555b66bf0) at ../Include/cpython/abstract.h:99 #41 method_vectorcall (method=, args=, nargsf=, kwnames=) at ../Objects/classobject.c:83 #42 0x00005555556bed67 in slot_tp_init (self=self@entry=, args=args@entry=('gstreamer_crash', '', , None, True, True), kwds=kwds@entry=0x0) at ../Objects/typeobject.c:7737 #43 0x00005555556aa98b in type_call (type=, args=('gstreamer_crash', '', , None, True, True), kwds=0x0) at ../Objects/typeobject.c:1135 #44 0x00007ffff66d5c51 in pybind11::detail::pybind11_meta_call(PyObject*, PyObject*, PyObject*) (type=, __doc__=None, __module__='rclpy._rclpy_pybind11', pointer=, get_fully_qualified_name=, logger_name=, get_node_name=, get_namespace=, get_count_publishers=, get_count_subscribers=, get_node_names_and_namespaces=, get_node_names_and_namespaces_with_enclaves=, get_action_client_names_and_types_by_node=, get_action_server_names_and_types_by_node=, get_action_names_and_types=, get_parameters=) at remote 0x555555d3e320>, args=('gstreamer_crash', '', , None, True, True), kwargs=0x0) at /usr/include/pybind11/detail/class.h:174 #45 0x00005555556aa5eb in _PyObject_MakeTpCall (tstate=0x555555b66bf0, callable=, __doc__=None, __module__='rclpy._rclpy_pybind11', pointer=, get_fully_qualified_name=, logger_name=, get_node_name=, get_namespace=, get_count_publishers=, get_count_subscribers=, get_node_names_and_namespaces=, get_node_names_and_namespaces_with_enclaves=, get_action_client_names_and_types_by_node=, get_action_server_names_and_types_by_node=, get_action_names_and_types=, get_parameters=) at remote 0x555555d3e320>, args=, nargs=, keywords=0x0) at ../Objects/call.c:215 #46 0x00005555556a31f1 in _PyObject_VectorcallTstate (kwnames=0x0, nargsf=, args=, callable=, __doc__=None, __module__='rclpy._rclpy_pybind11', pointer=, get_fully_qualified_name=, logger_name=, get_node_name=, get_namespace=, get_count_publishers=, get_count_subscribers=, get_node_names_and_namespaces=, get_node_names_and_namespaces_with_enclaves=, get_action_client_names_and_types_by_node=, get_action_server_names_and_types_by_node=, get_action_names_and_types=, get_parameters=) at remote 0x555555d3e320>, tstate=) at ../Include/cpython/abstract.h:112 #47 _PyObject_VectorcallTstate (kwnames=0x0, nargsf=, args=0x555555e801e8, callable=, __doc__=None, __module__='rclpy._rclpy_pybind11', pointer=, get_fully_qualified_name=, logger_name=, get_node_name=, get_namespace=, get_count_publishers=, get_count_subscribers=, get_node_names_and_namespaces=, get_node_names_and_namespaces_with_enclaves=, get_action_client_names_and_types_by_node=, get_action_server_names_and_types_by_node=, get_action_names_and_types=, get_parameters=) at remote 0x555555d3e320>, tstate=) at ../Include/cpython/abstract.h:99 #48 PyObject_Vectorcall (kwnames=0x0, nargsf=, args=0x555555e801e8, callable=, __doc__=None, __module__='rclpy._rclpy_pybind11', pointer=, get_fully_qualified_name=, logger_name=, get_node_name=, get_namespace=, get_count_publishers=, get_count_subscribers=, get_node_names_and_namespaces=, get_node_names_and_namespaces_with_enclaves=, get_action_client_names_and_types_by_node=, get_action_server_names_and_types_by_node=, get_action_names_and_types=, get_parameters=) at remote 0x555555d3e320>) at ../Include/cpython/abstract.h:123 #49 call_function (kwnames=0x0, oparg=, pp_stack=, trace_info=0x7fffffffbae0, tstate=) at ../Python/ceval.c:5893 #50 _PyEval_EvalFrameDefault (tstate=, f=, throwflag=) at ../Python/ceval.c:4181 #51 0x00005555556b470c in _PyEval_EvalFrame (throwflag=0, f=Frame 0x555555e80010, for file /home/chenlh/Projects/ROS2/ros2-master/install/lib/python3.10/site-packages/rclpy/node.py, line 185, in __init__ (self=, _callbacks=[], _logging_initialized=True, _Context__context=) at remote 0x7ffff6fcff10>, _parameters={}, _publishers=[], _subscriptions=[], _clients=[], _services=[], _timers=[], _guards=[], _Node__waitables=[], _default_callback_group=) at remote 0x7ffff6ba2dd0>, _pre_set_parameters_callbacks=[], _on_set_parameters_callbacks=[], _post_set_parameters_callbacks=[], _rate_group=, _allow_undeclared_parameters=False, _parameter_overrides={}, _descriptors={}) at remote 0x7ffff6d27940>, node_name='gstreamer_crash', context=None, cli_args=None, name...(truncated), tstate=0x555555b66bf0) at ../Include/internal/pycore_ceval.h:46 #52 _PyEval_Vector (kwnames=, argcount=, args=, locals=0x0, con=0x7ffff0db2840, tstate=0x555555b66bf0) at ../Python/ceval.c:5067 #53 _PyFunction_Vectorcall (func=, stack=, nargsf=, kwnames=) at ../Objects/call.c:342 #54 0x00005555556a982d in _PyObject_FastCallDictTstate (tstate=0x555555b66bf0, callable=, args=, nargsf=, kwargs=) at ../Objects/call.c:153 #55 0x00005555556be744 in _PyObject_Call_Prepend (kwargs={'context': None, 'cli_args': None, 'namespace': None, 'use_global_arguments': True, 'enable_rosout': True, 'start_parameter_services': True, 'parameter_overrides': None, 'allow_undeclared_parameters': False, 'automatically_declare_parameters_from_overrides': False, 'enable_logger_service': False}, args=('gstreamer_crash',), obj=, _callbacks=[], _logging_initialized=True, _Context__context=) at remote 0x7ffff6fcff10>, _parameters={}, _publishers=[], _subscriptions=[], _clients=[], _services=[], _timers=[], _guards=[], _Node__waitables=[], _default_callback_group=) at remote 0x7ffff6ba2dd0>, _pre_set_parameters_callbacks=[], _on_set_parameters_callbacks=[], _post_set_parameters_callbacks=[], _rate_group=, _allow_undeclared_parameters=False, _parameter_overrides={}, _descriptors={}) at remote 0x7ffff6d27940>, callable=, tstate=0x555555b66bf0) at ../Objects/call.c:431 #56 slot_tp_init (self=self@entry=, _callbacks=[], _logging_initialized=True, _Context__context=) at remote 0x7ffff6fcff10>, _parameters={}, _publishers=[], _subscriptions=[], _clients=[], _services=[], _timers=[], _guards=[], _Node__waitables=[], _default_callback_group=) at remote 0x7ffff6ba2dd0>, _pre_set_parameters_callbacks=[], _on_set_parameters_callbacks=[], _post_set_parameters_callbacks=[], _rate_group=, _allow_undeclared_parameters=False, _parameter_overrides={}, _descriptors={}) at remote 0x7ffff6d27940>, args=args@entry=('gstreamer_crash',), kwds=kwds@entry={'context': None, 'cli_args': None, 'namespace': None, 'use_global_arguments': True, 'enable_rosout': True, 'start_parameter_services': True, 'parameter_overrides': None, 'allow_undeclared_parameters': False, 'automatically_declare_parameters_from_overrides': False, 'enable_logger_service': False}) at ../Objects/typeobject.c:7734 #57 0x00005555556aa58c in type_call (kwds={'context': None, 'cli_args': None, 'namespace': None, 'use_global_arguments': True, 'enable_rosout': True, 'start_parameter_services': True, 'parameter_overrides': None, 'allow_undeclared_parameters': False, 'automatically_declare_parameters_from_overrides': False, 'enable_logger_service': False}, args=('gstreamer_crash',), type=) at ../Objects/typeobject.c:1135 #58 _PyObject_MakeTpCall (tstate=0x555555b66bf0, callable=, args=, nargs=, keywords=('context', 'cli_args', 'namespace', 'use_global_arguments', 'enable_rosout', 'start_parameter_services', 'parameter_overrides', 'allow_undeclared_parameters', 'automatically_declare_parameters_from_overrides', 'enable_logger_service')) at ../Objects/call.c:215 #59 0x00005555556a3908 in _PyObject_VectorcallTstate (kwnames=('context', 'cli_args', 'namespace', 'use_global_arguments', 'enable_rosout', 'start_parameter_services', 'parameter_overrides', 'allow_undeclared_parameters', 'automatically_declare_parameters_from_overrides', 'enable_logger_service'), nargsf=, args=, callable=, tstate=0x555555b66bf0) at ../Include/cpython/abstract.h:112 #60 _PyObject_VectorcallTstate (kwnames=('context', 'cli_args', 'namespace', 'use_global_arguments', 'enable_rosout', 'start_parameter_services', 'parameter_overrides', 'allow_undeclared_parameters', 'automatically_declare_parameters_from_overrides', 'enable_logger_service'), nargsf=, args=, callable=, tstate=0x555555b66bf0) at ../Include/cpython/abstract.h:99 #61 PyObject_Vectorcall (kwnames=('context', 'cli_args', 'namespace', 'use_global_arguments', 'enable_rosout', 'start_parameter_services', 'parameter_overrides', 'allow_undeclared_parameters', 'automatically_declare_parameters_from_overrides', 'enable_logger_service'), nargsf=, args=, callable=) at ../Include/cpython/abstract.h:123 #62 call_function (kwnames=('context', 'cli_args', 'namespace', 'use_global_arguments', 'enable_rosout', 'start_parameter_services', 'parameter_overrides', 'allow_undeclared_parameters', 'automatically_declare_parameters_from_overrides', 'enable_logger_service'), oparg=, pp_stack=, trace_info=0x7fffffffbe30, tstate=) at ../Python/ceval.c:5893 #63 _PyEval_EvalFrameDefault (tstate=, f=, throwflag=) at ../Python/ceval.c:4231 #64 0x00005555556b470c in _PyEval_EvalFrame (throwflag=0, f=Frame 0x555555eb1920, for file /home/chenlh/Projects/ROS2/ros2-master/install/lib/python3.10/site-packages/rclpy/__init__.py, line 180, in create_node (node_name='gstreamer_crash', context=None, cli_args=None, namespace=None, use_global_arguments=True, enable_rosout=True, start_parameter_services=True, parameter_overrides=None, allow_undeclared_parameters=False, automatically_declare_parameters_from_overrides=False, enable_logger_service=False, Node=), tstate=0x555555b66bf0) at ../Include/internal/pycore_ceval.h:46 #65 _PyEval_Vector (kwnames=, argcount=, args=, locals=0x0, con=0x7ffff6a1e690, tstate=0x555555b66bf0) at ../Python/ceval.c:5067 #66 _PyFunction_Vectorcall (func=, stack=, nargsf=, kwnames=) at ../Objects/call.c:342 #67 0x00005555556a28a2 in _PyObject_VectorcallTstate (kwnames=0x0, nargsf=, args=0x7ffff6e3f9b0, callable=, tstate=0x555555b66bf0) at ../Include/cpython/abstract.h:114 #68 PyObject_Vectorcall (kwnames=0x0, nargsf=, args=0x7ffff6e3f9b0, callable=) at ../Include/cpython/abstract.h:123 #69 call_function (kwnames=0x0, oparg=, pp_stack=, trace_info=0x7fffffffc010, tstate=) at ../Python/ceval.c:5893 #70 _PyEval_EvalFrameDefault (tstate=, f=, throwflag=) at ../Python/ceval.c:4181 #71 0x000055555578de56 in _PyEval_EvalFrame (throwflag=0, f=Frame 0x7ffff6e3f840, for file /home/chenlh/Projects/ROS2/ros2-master/gst_rclpy.py, line 30, in (), tstate=0x555555b66bf0) at ../Include/internal/pycore_ceval.h:46 #72 _PyEval_Vector (tstate=0x555555b66bf0, con=, locals=, args=, argcount=, kwnames=) at ../Python/ceval.c:5067 #73 0x000055555578dcf6 in PyEval_EvalCode (co=, globals={'__name__': '__main__', '__doc__': None, '__package__': None, '__loader__': , '__spec__': None, '__annotations__': {}, '__builtins__': , '__file__': '/home/chenlh/Projects/ROS2/ros2-master/gst_rclpy.py', '__cached__': None, 'sys': , 'time': , 'rclpy': , 'gi': , 'Gst': , __spec__=, origin=None, loader_state=None, submodule_search_locations=None, _set_fileattr=False, _cached=None) at remote 0x7ffff6a63eb0>, _introspection_module=) at ../Python/ceval.c:1134 #74 0x00005555557b87d8 in run_eval_code_obj (tstate=0x555555b66bf0, co=0x7ffff6ef5dc0, globals={'__name__': '__main__', '__doc__': None, '__package__': None, '__loader__': , '__spec__': None, '__annotations__': {}, '__builtins__': , '__file__': '/home/chenlh/Projects/ROS2/ros2-master/gst_rclpy.py', '__cached__': None, 'sys': , 'time': , 'rclpy': , 'gi': , 'Gst': , __spec__=, origin=None, loader_state=None, submodule_search_locations=None, _set_fileattr=False, _cached=None) at remote 0x7ffff6a63eb0>, _introspection_module=, '__spec__': None, '__annotations__': {}, '__builtins__': , '__file__': '/home/chenlh/Projects/ROS2/ros2-master/gst_rclpy.py', '__cached__': None, 'sys': , 'time': , 'rclpy': , 'gi': , 'Gst': , __spec__=, origin=None, loader_state=None, submodule_search_locations=None, _set_fileattr=False, _cached=None) at remote 0x7ffff6a63eb0>, _introspection_module=, filename=, globals={'__name__': '__main__', '__doc__': None, '__package__': None, '__loader__': , '__spec__': None, '__annotations__': {}, '__builtins__': , '__file__': '/home/chenlh/Projects/ROS2/ros2-master/gst_rclpy.py', '__cached__': None, 'sys': , 'time': , 'rclpy': , 'gi': , 'Gst': , __spec__=, origin=None, loader_state=None, submodule_search_locations=None, _set_fileattr=False, _cached=None) at remote 0x7ffff6a63eb0>, _introspection_module=, '__spec__': None, '__annotations__': {}, '__builtins__': , '__file__': '/home/chenlh/Projects/ROS2/ros2-master/gst_rclpy.py', '__cached__': None, 'sys': , 'time': , 'rclpy': , 'gi': , 'Gst': , __spec__=, origin=None, loader_state=None, submodule_search_locations=None, _set_fileattr=False, _cached=None) at remote 0x7ffff6a63eb0>, _introspection_module=, arena=) at ../Python/pythonrun.c:1312 #76 0x00005555557b8525 in pyrun_file (fp=fp@entry=0x555555b44f20, filename=filename@entry='/home/chenlh/Projects/ROS2/ros2-master/gst_rclpy.py', start=start@entry=257, globals=globals@entry={'__name__': '__main__', '__doc__': None, '__package__': None, '__loader__': , '__spec__': None, '__annotations__': {}, '__builtins__': , '__file__': '/home/chenlh/Projects/ROS2/ros2-master/gst_rclpy.py', '__cached__': None, 'sys': , 'time': , 'rclpy': , 'gi': , 'Gst': , __spec__=, origin=None, loader_state=None, submodule_search_locations=None, _set_fileattr=False, _cached=None) at remote 0x7ffff6a63eb0>, _introspection_module=, '__spec__': None, '__annotations__': {}, '__builtins__': , '__file__': '/home/chenlh/Projects/ROS2/ros2-master/gst_rclpy.py', '__cached__': None, 'sys': , 'time': , 'rclpy': , 'gi': , 'Gst': , __spec__=, origin=None, loader_state=None, submodule_search_locations=None, _set_fileattr=False, _cached=None) at remote 0x7ffff6a63eb0>, _introspection_module=, argv=) at ../Modules/main.c:720 #84 0x00007ffff7c29d90 in __libc_start_call_main (main=main@entry=0x555555780c70
, argc=argc@entry=2, argv=argv@entry=0x7fffffffc4c8) at ../sysdeps/nptl/libc_start_call_main.h:58 #85 0x00007ffff7c29e40 in __libc_start_main_impl (main=0x555555780c70
, argc=2, argv=0x7fffffffc4c8, init=, fini=, rtld_fini=, stack_end=0x7fffffffc4b8) at ../csu/libc-start.c:392 #86 0x0000555555780ba5 in _start () (gdb) c Continuing. Thread 1 "python3" received signal SIGSEGV, Segmentation fault. read_encoded_value_with_base (encoding=176 '\260', base=, p=0x7fffffff1549 "\003", val=0x7fffffff0c68) at /build/gcc-12-ALHxjy/gcc-12-12.3.0/src/libstdc++-v3/../libgcc/unwind-pe.h:284 284 /build/gcc-12-ALHxjy/gcc-12-12.3.0/src/libstdc++-v3/../libgcc/unwind-pe.h: No such file or directory. (gdb) ```

without gstream

```shell chenlh ros2-master $ gdb /usr/bin/python3 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 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: . Find the GDB manual and other documentation resources online at: . For help, type "help". Type "apropos word" to search for commands related to "word"... Reading symbols from /usr/bin/python3... Reading symbols from /usr/lib/debug/.build-id/8d/f1c7df42f40a5fa606666db1b65c8d9a4ddfe4.debug... (gdb) b _Unwind_RaiseException Function "_Unwind_RaiseException" not defined. Breakpoint 1 (_Unwind_RaiseException) pending. (gdb) b _Unwind_Resume Function "_Unwind_Resume" not defined. Breakpoint 2 (_Unwind_Resume) pending. (gdb) r gst_rclpy.py Starting program: /usr/bin/python3 gst_rclpy.py [Thread debugging using libthread_db enabled] Using host libthread_db library "/lib/x86_64-linux-gnu/libthread_db.so.1". warning: File "/usr/lib/x86_64-linux-gnu/debug/libstdc++.so.6.0.30-gdb.py" auto-loading has been declined by your `auto-load safe-path' set to "$debugdir:$datadir/auto-load". To enable execution of this file add add-auto-load-safe-path /usr/lib/x86_64-linux-gnu/debug/libstdc++.so.6.0.30-gdb.py line to your configuration file "/home/chenlh/.gdbinit". To completely disable this security protection add set auto-load safe-path / line to your configuration file "/home/chenlh/.gdbinit". For more information about this security protection see the "Auto-loading safe path" section in the GDB manual. E.g., run from the shell: info "(gdb)Auto-loading safe path" [New Thread 0x7ffff4f8e640 (LWP 796769)] [New Thread 0x7ffff23ff640 (LWP 797037)] init [New Thread 0x7ffff1bfe640 (LWP 797048)] [New Thread 0x7ffff13fd640 (LWP 797049)] [New Thread 0x7ffff0bfc640 (LWP 797051)] [New Thread 0x7ffff03fb640 (LWP 797054)] [New Thread 0x7fffefbfa640 (LWP 797055)] Thread 1 "python3" hit Breakpoint 1, 0x00007ffff5f65c38 in _Unwind_RaiseException () from /lib/x86_64-linux-gnu/libgcc_s.so.1 (gdb) c Continuing. Thread 1 "python3" hit Breakpoint 2, 0x00007ffff5f661b8 in _Unwind_Resume () from /lib/x86_64-linux-gnu/libgcc_s.so.1 (gdb) c Continuing. Thread 1 "python3" hit Breakpoint 2, 0x00007ffff5f661b8 in _Unwind_Resume () from /lib/x86_64-linux-gnu/libgcc_s.so.1 (gdb) Continuing. Thread 1 "python3" hit Breakpoint 2, 0x00007ffff5f661b8 in _Unwind_Resume () from /lib/x86_64-linux-gnu/libgcc_s.so.1 (gdb) Continuing. Thread 1 "python3" hit Breakpoint 2, 0x00007ffff5f661b8 in _Unwind_Resume () from /lib/x86_64-linux-gnu/libgcc_s.so.1 (gdb) Continuing. Thread 1 "python3" hit Breakpoint 2, 0x00007ffff5f661b8 in _Unwind_Resume () from /lib/x86_64-linux-gnu/libgcc_s.so.1 (gdb) Continuing. [New Thread 0x7fffef3f9640 (LWP 798494)] [New Thread 0x7fffeeb38640 (LWP 798495)] [New Thread 0x7fffee337640 (LWP 798574)] [New Thread 0x7fffddfff640 (LWP 799066)] [New Thread 0x7fffdd7fe640 (LWP 799067)] [New Thread 0x7fffdcffd640 (LWP 799068)] [New Thread 0x7fffd3fff640 (LWP 799069)] [New Thread 0x7fffd17fe640 (LWP 799070)] [New Thread 0x7fffccffd640 (LWP 799071)] [New Thread 0x7fffcc7fc640 (LWP 799072)] [New Thread 0x7fffc9ffb640 (LWP 799073)] [New Thread 0x7fffc77fa640 (LWP 799074)] [New Thread 0x7fffc2ff9640 (LWP 799075)] [New Thread 0x7fffc27f8640 (LWP 799076)] [New Thread 0x7fffbfff7640 (LWP 799077)] [New Thread 0x7fffbd7f6640 (LWP 799078)] [New Thread 0x7fffbcff5640 (LWP 799079)] [New Thread 0x7fffba7f4640 (LWP 799080)] after node ```

What I expect is to use these unwind functions in either gcc(1,2) or libunwind(1,2) durning throw.

iuhilnehc-ynos commented 11 months ago

One final solution I can figure out is to use the LD_PRELOAD.

e.g.
$ export LD_PRELOAD=/usr/lib/x86_64-linux-gnu/libunwind.so.8
$ python3 gst_rclpy.py

NOTE that libgstreamer-1.0.so.0 depends on the libunwind.so.8.

jwakely commented 11 months ago

If libgstreamer-1.0.so.0 includes the linunwind symbols then it should use a linker script to avoid them being exported. Otherwise you get incompatible symbols with the same name.

russkel commented 2 months ago

If libgstreamer-1.0.so.0 includes the linunwind symbols then it should use a linker script to avoid them being exported. Otherwise you get incompatible symbols with the same name.

ros@kalesmoothie:/greenstream-packages$ nm -gD /usr/lib/x86_64-linux-gnu/libgstreamer-1.0.so | grep -i unwind
ros@kalesmoothie:/greenstream-packages$ 

This is on ubuntu noble.