ZettaScaleLabs / rmw_zenoh

RMW for ROS 2 using Zenoh as the middleware
Apache License 2.0
0 stars 0 forks source link

Panic while running the nav2 #26

Open evshary opened 2 weeks ago

evshary commented 2 weeks ago
[create-3] thread '<unnamed>' panicked at /rustc/82e1608dfa6e0b5569232559e3d385fea5a93112/library/std/src/thread/local.rs:246:26:
[create-3] cannot access a Thread Local Storage value during or after destruction: AccessError
[create-3] note: run with `RUST_BACKTRACE=1` environment variable to display a backtrace

We can have a workaround by commenting the z_close for the time being.

evshary commented 1 week ago

The crash comes from https://github.com/gazebosim/ros_gz/blob/ros2/ros_gz_sim/src/create.cpp We can see that there is no rclcpp::shutdown() and it will shutdown in the Context deconstructor in rclcpp https://github.com/ros2/rclcpp/blob/0be8aa013e4ed94bcab88527887e85130816d256/rclcpp/src/rclcpp/context.cpp#L320

I guess there is no ownership of Zenoh session after leaving main func. Then Zenoh session is released, so we can't shudown it in the deconstructor.

evshary commented 1 week ago
#11 0x00007ffff59b9cd1 in std::panicking::begin_panic_handler (info=<optimized out>)                                                                                                                        
    at library/std/src/panicking.rs:645                                                                                                                                                                     
#12 0x00007ffff56b3a84 in core::panicking::panic_fmt (fmt=...) at library/core/src/panicking.rs:72                                                                                                          
#13 0x00007ffff56b41a2 in core::result::unwrap_failed (msg=..., error=...)                                                                                                                                  
--Type <RET> for more, q to quit, c to continue without paging--                                                                                                                                            
    at library/core/src/result.rs:1653                                                                                                                                                                      
#14 0x00007ffff580a999 in z_close ()                                                                                                                                                                        
   from /home/evshary/workspace/ros2_rolling_rmw_zenoh_ws/install/zenoh_c_vendor/opt/zenoh_c_vendor/lib/libzenohc.so                                                                                        
#15 0x00007ffff7364476 in rmw_context_impl_s::Data::shutdown() ()                                                                                                                                           
   from /home/evshary/workspace/ros2_rolling_rmw_zenoh_ws/install/rmw_zenoh_cpp/lib/librmw_zenoh_cpp.so                                                                                                     
#16 0x00007ffff73655ce in rmw_context_impl_s::shutdown() ()                                                                                                                                                 
   from /home/evshary/workspace/ros2_rolling_rmw_zenoh_ws/install/rmw_zenoh_cpp/lib/librmw_zenoh_cpp.so 
#17 0x00007ffff7394a12 in rmw_shutdown ()                                                                                                                                                            [0/785]
   from /home/evshary/workspace/ros2_rolling_rmw_zenoh_ws/install/rmw_zenoh_cpp/lib/librmw_zenoh_cpp.so
#18 0x00007ffff7d321a5 in rcl_shutdown () from /opt/ros/rolling/lib/librcl.so                                                                                                                               
#19 0x00007ffff7e4d57f in rclcpp::Context::shutdown(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&) () from /opt/ros/rolling/lib/librclcpp.so
#20 0x00007ffff7e4de05 in rclcpp::Context::~Context() () from /opt/ros/rolling/lib/librclcpp.so                                                                                                             
#21 0x00007ffff7e46ba6 in ?? () from /opt/ros/rolling/lib/librclcpp.so                                                                                                                                      
#22 0x00007ffff7862a66 in __run_exit_handlers (status=0, listp=<optimized out>,                                                                                                                             
    run_list_atexit=run_list_atexit@entry=true, run_dtors=run_dtors@entry=true)                                                                                                                             
    at ./stdlib/exit.c:108                                                                           
#23 0x00007ffff7862bae in __GI_exit (status=<optimized out>) at ./stdlib/exit.c:138
#24 0x00007ffff78451d1 in __libc_start_call_main (main=main@entry=0x5555555a9e9a <main>, 
    argc=argc@entry=1, argv=argv@entry=0x7fffffffb0d8) at ../sysdeps/nptl/libc_start_call_main.h:74
--Type <RET> for more, q to quit, c to continue without paging--                                                                                                                                            
#25 0x00007ffff784528b in __libc_start_main_impl (main=0x5555555a9e9a <main>, argc=1, 
    argv=0x7fffffffb0d8, init=<optimized out>, fini=<optimized out>, rtld_fini=<optimized out>, 
    stack_end=0x7fffffffb0c8) at ../csu/libc-start.c:360                                                                                                                                                    
#26 0x00005555555a9c35 in _start ()

This is the gdb backtrace and it seems like if we don't shutdown explicitly, it will be called in atexit. Due to the issue here, it seems like there is no proper way to do so.

evshary commented 6 days ago

Add rclcpp::shutdown() to ros_gz_sim to avoid the issue temporarily https://github.com/gazebosim/ros_gz/pull/623