ros-drivers / ros2_ouster_drivers

ROS2 Drivers for the Ouster OS-0, OS-1, and OS-2 Lidars
https://ouster.com/
Apache License 2.0
136 stars 79 forks source link

Lifecycle publishers with FastRTPS crashing #19

Closed SteveMacenski closed 4 years ago

SteveMacenski commented 4 years ago

I've validated the object exists and is allocated, the messages have been printed and are complete, but a bunch of the time, especially with the PCL-used image / pointcloud publishers it crashes when it tries to publish a message. See traceback below.

I cant tell if its a RMW, ROS, PCL, or my software problem. But its stopping me from being able to publish data other than IMU.

Occasionally I get it to work and I can see in rviz the data is good, so I really don't think its related to the data handling from the lidar.

Thread 1 "ouster_driver" received signal SIGSEGV, Segmentation fault.
do_lookup_x (
    undef_name=undef_name@entry=0x7fffd77cef0a "_ZN11sensor_msgs3msg24typesupport_fastrtps_cpp19get_serialized_sizeERKNS0_4Imu_ISaIvEEEm", 
    new_hash=new_hash@entry=1679295439, old_hash=old_hash@entry=0x7fffffffaa40, 
    ref=0x7fffd77cc208, result=result@entry=0x7fffffffaa50, scope=<optimized out>, 
    i=63, version=0x0, flags=5, skip=0x0, type_class=1, undef_map=0x555555a92450)
    at dl-lookup.c:360
360 dl-lookup.c: No such file or directory.
(gdb) traceback
Undefined command: "traceback".  Try "help".
(gdb) backtrace
#0  do_lookup_x (
    undef_name=undef_name@entry=0x7fffd77cef0a "_ZN11sensor_msgs3msg24typesupport_fastrtps_cpp19get_serialized_sizeERKNS0_4Imu_ISaIvEEEm", 
    new_hash=new_hash@entry=1679295439, old_hash=old_hash@entry=0x7fffffffaa40, 
    ref=0x7fffd77cc208, result=result@entry=0x7fffffffaa50, scope=<optimized out>, 
    i=63, version=0x0, flags=5, skip=0x0, type_class=1, undef_map=0x555555a92450)
    at dl-lookup.c:360
#1  0x00007ffff7de01ef in _dl_lookup_symbol_x (
    undef_name=0x7fffd77cef0a "_ZN11sensor_msgs3msg24typesupport_fastrtps_cpp19get_serialized_sizeERKNS0_4Imu_ISaIvEEEm", undef_map=0x555555a92450, 
    ref=ref@entry=0x7fffffffaae8, symbol_scope=0x555555a927a8, version=0x0, 
    type_class=type_class@entry=1, flags=5, skip_map=<optimized out>)
    at dl-lookup.c:813
#2  0x00007ffff7de4ec3 in _dl_fixup (l=<optimized out>, reloc_arg=<optimized out>)
    at ../elf/dl-runtime.c:112
#3  0x00007ffff7dec7ca in _dl_runtime_resolve_xsavec ()
    at ../sysdeps/x86_64/dl-trampoline.h:125
#4  0x00007fffd77da22b in ?? ()
   from /opt/ros/eloquent/lib/libsensor_msgs__rosidl_typesupport_fastrtps_cpp.so
#5  0x00007ffff0ebb077 in ?? () from /opt/ros/eloquent/lib/librmw_fastrtps_cpp.so
#6  0x00007ffff0a885ad in ?? ()
   from /opt/ros/eloquent/lib/librmw_fastrtps_shared_cpp.so
#7  0x00007ffff0420401 in eprosima::fastrtps::rtps::CacheChangePool::reserve_Cache(eprosima::fastrtps::rtps::CacheChange_t**, std::function<unsigned int ()> const&) ()
   from /opt/ros/eloquent/lib/libfastrtps.so.1
#8  0x00007ffff03ffd82 in eprosima::fastrtps::rtps::RTPSWriter::new_change(std::function<unsigned int ()> const&, eprosima::fastrtps::rtps::ChangeKind_t, eprosima::fastrtps::rtps::InstanceHandle_t) () from /opt/ros/eloquent/lib/libfastrtps.so.1
#9  0x00007ffff0488c3d in eprosima::fastrtps::PublisherImpl::create_new_change_with_params(eprosima::fastrtps::rtps::ChangeKind_t, void*, eprosima::fastrtps::rtps::WriteParams&) () from /opt/ros/eloquent/lib/libfastrtps.so.1
#10 0x00007ffff048b370 in eprosima::fastrtps::PublisherImpl::create_new_change(eprosima::fastrtps::rtps::ChangeKind_t, void*) ()
   from /opt/ros/eloquent/lib/libfastrtps.so.1
#11 0x00007ffff0a8304d in rmw_fastrtps_shared_cpp::__rmw_publish(char const*, rmw_publisher_t const*, void const*, rmw_publisher_allocation_t*) ()
   from /opt/ros/eloquent/lib/librmw_fastrtps_shared_cpp.so
#12 0x00007ffff5a3ae3f in rcl_publish () from /opt/ros/eloquent/lib/librcl.so
#13 0x00007ffff7b4d608 in rclcpp::Publisher<sensor_msgs::msg::Imu_<std::allocator<void> >, std::allocator<void> >::do_inter_process_publish(sensor_msgs::msg::Imu_<std::allocator<void> > const&) ()
   from /home/steve/Documents/ouster_ws2/install/ros2_ouster/lib/libouster_driver_core.so
#14 0x00007ffff7b48120 in rclcpp::Publisher<sensor_msgs::msg::Imu_<std::allocator<void> >, std::allocator<void> >::publish(sensor_msgs::msg::Imu_<std::allocator<void> > const&) ()
   from /home/steve/Documents/ouster_ws2/install/ros2_ouster/lib/libouster_driver_core.so
#15 0x00007ffff7b4346a in rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::Imu_<std::allocator<void> >, std::allocator<void> >::publish(sensor_msgs::msg::Imu_<std::allocator<void> > const&) ()
   from /home/steve/Documents/ouster_ws2/install/ros2_ouster/lib/libouster_driver_co---Type <return> to continue, or q <return> to quit---
re.so
#16 0x00007ffff7b3b6d5 in OS1::IMUProcessor::process(unsigned char*) ()
   from /home/steve/Documents/ouster_ws2/install/ros2_ouster/lib/libouster_driver_core.so
#17 0x00007ffff7b3ec0d in ros2_ouster::OusterDriver<OS1::OS1Sensor>::processData()
    ()
   from /home/steve/Documents/ouster_ws2/install/ros2_ouster/lib/libouster_driver_core.so
#18 0x00007ffff7b85a61 in void std::__invoke_impl<void, void (ros2_ouster::OusterDriver<OS1::OS1Sensor>::*&)(), ros2_ouster::OusterDriver<OS1::OS1Sensor>*&>(std::__invoke_memfun_deref, void (ros2_ouster::OusterDriver<OS1::OS1Sensor>::*&)(), ros2_ouster::OusterDriver<OS1::OS1Sensor>*&) ()
   from /home/steve/Documents/ouster_ws2/install/ros2_ouster/lib/libouster_driver_core.so
#19 0x00007ffff7b8504a in std::__invoke_result<void (ros2_ouster::OusterDriver<OS1::OS1Sensor>::*&)(), ros2_ouster::OusterDriver<OS1::OS1Sensor>*&>::type std::__invoke<void (ros2_ouster::OusterDriver<OS1::OS1Sensor>::*&)(), ros2_ouster::OusterDriver<OS1::OS1Sensor>*&>(void (ros2_ouster::OusterDriver<OS1::OS1Sensor>::*&)(), ros2_ouster::OusterDriver<OS1::OS1Sensor>*&) ()
   from /home/steve/Documents/ouster_ws2/install/ros2_ouster/lib/libouster_driver_core.so
#20 0x00007ffff7b8447b in void std::_Bind<void (ros2_ouster::OusterDriver<OS1::OS1Sensor>::*(ros2_ouster::OusterDriver<OS1::OS1Sensor>*))()>::__call<void, , 0ul>(std::tuple<>&&, std::_Index_tuple<0ul>) ()
   from /home/steve/Documents/ouster_ws2/install/ros2_ouster/lib/libouster_driver_core.so
#21 0x00007ffff7b82b41 in void std::_Bind<void (ros2_ouster::OusterDriver<OS1::OS1Sensor>::*(ros2_ouster::OusterDriver<OS1::OS1Sensor>*))()>::operator()<, void>() ()
   from /home/steve/Documents/ouster_ws2/install/ros2_ouster/lib/libouster_driver_core.so
#22 0x00007ffff7b81508 in void rclcpp::GenericTimer<std::_Bind<void (ros2_ouster::OusterDriver<OS1::OS1Sensor>::*(ros2_ouster::OusterDriver<OS1::OS1Sensor>*))()>, (void*)0>::execute_callback_delegate<std::_Bind<void (ros2_ouster::OusterDriver<OS1::OS1Sensor>::*(ros2_ouster::OusterDriver<OS1::OS1Sensor>*))()>, (void*)0>() ()
   from /home/steve/Documents/ouster_ws2/install/ros2_ouster/lib/libouster_driver_core.so
#23 0x00007ffff7b7f4b4 in rclcpp::GenericTimer<std::_Bind<void (ros2_ouster::OusterDriver<OS1::OS1Sensor>::*(ros2_ouster::OusterDriver<OS1::OS1Sensor>*))()>, (void*)0>::execute_callback() ()
   from /home/steve/Documents/ouster_ws2/install/ros2_ouster/lib/libouster_driver_core.so
#24 0x00007ffff72fdfb5 in rclcpp::executor::Executor::execute_any_executable(rclcpp::executor::AnyExecutable&) () from /opt/ros/eloquent/lib/librclcpp.so
#25 0x00007ffff73046ef in rclcpp::executors::SingleThreadedExecutor::spin() ()
   from /opt/ros/eloquent/lib/librclcpp.so
#26 0x00007ffff73013e2 in rclcpp::spin(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>) () from /opt/ros/eloquent/lib/librclcpp.so
#27 0x00005555555616da in main ()
Samuellee1986 commented 4 years ago

Do you know the reason why it crashes?