Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Segmentation fault on laser scan #213

Closed
maxlein opened this issue Dec 3, 2019 · 16 comments
Closed

Segmentation fault on laser scan #213

maxlein opened this issue Dec 3, 2019 · 16 comments
Assignees
Labels
bug Something isn't working

Comments

@maxlein
Copy link

maxlein commented Dec 3, 2019

I got some SIGABRT and SIGSEGV when using message filters in slam_toolbox.
Maybe you guys can better help out here.

The issue is described in detail here.

Basically what I saw is that memory usage is increasing and after ~1,2 hours the node crashes.

[Thread debugging using libthread_db enabled]
Using host libthread_db library "/lib/x86_64-linux-gnu/libthread_db.so.1".
Core was generated by `/home/kin/playground_ws/install/slam_toolbox/lib/slam_toolbox/localization_slam'.
Program terminated with signal SIGSEGV, Segmentation fault.
#0  0x00007f6958cf2977 in tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> > >::add (this=0x7f69003d1850, evt=...) at /opt/ros/dashing/include/tf2_ros/message_filter.h:378
378               bc_.cancelTransformableRequest(*it);
[Current thread is 1 (Thread 0x7f69593f5f40 (LWP 23208))]
(gdb) backtrace
#0  0x00007f6958cf2977 in tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> > >::add (this=0x7f69003d1850, evt=...) at /opt/ros/dashing/include/tf2_ros/message_filter.h:378
ros2/message_filters#1  0x00007f6958cf05dc in std::function<void (message_filters::MessageEvent<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&)>::operator()(message_filters::MessageEvent<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&) const (__args#0=..., this=0x561eabee6018) at /usr/include/c++/7/bits/std_function.h:706
ros2/message_filters#2  message_filters::CallbackHelper1T<message_filters::MessageEvent<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&, sensor_msgs::msg::LaserScan_<std::allocator<void> > >::call (this=0x561eabee6010, 
    event=..., nonconst_force_copy=<optimized out>) at /opt/ros/dashing/include/message_filters/signal1.h:74
ros2/message_filters#3  0x00007f6958cee6b0 in message_filters::Signal1<sensor_msgs::msg::LaserScan_<std::allocator<void> > >::call (event=..., this=0x561eac00bb98) at /opt/ros/dashing/include/message_filters/signal1.h:117
ros2/message_filters#4  message_filters::SimpleFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> > >::signalMessage (event=..., this=0x561eac00bb98) at /opt/ros/dashing/include/message_filters/simple_filter.h:133
ros2/message_filters#5  message_filters::Subscriber<sensor_msgs::msg::LaserScan_<std::allocator<void> > >::cb (e=..., this=0x561eac00bb90) at /opt/ros/dashing/include/message_filters/subscriber.h:235
ros2/message_filters#6  message_filters::Subscriber<sensor_msgs::msg::LaserScan_<std::allocator<void> > >::subscribe(rclcpp::Node*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rmw_qos_profile_t)::{lambda(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>)#1}::operator()(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>) const (msg=..., __closure=<optimized out>)
    at /opt/ros/dashing/include/message_filters/subscriber.h:174
ros2/message_filters#7  std::_Function_handler<void (std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>), message_filters::Subscriber<sensor_msgs::msg::LaserScan_<std::allocator<void> > >::subscribe(rclcpp::Node*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rmw_qos_profile_t)::{lambda(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>)#1}>::_M_invoke(std::_Any_data const&, std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>&&) (__functor=..., __args#0=...) at /usr/include/c++/7/bits/std_function.h:316
ros2/message_filters#8  0x00007f6958d17d24 in std::function<void (std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>)>::operator()(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>) const (
    __args#0=std::shared_ptr<const sensor_msgs::msg::LaserScan_<std::allocator<void> >> (empty) = {...}, this=0x561eac00c370) at /usr/include/c++/7/bits/std_function.h:706
ros2/message_filters#9  rclcpp::AnySubscriptionCallback<sensor_msgs::msg::LaserScan_<std::allocator<void> >, std::allocator<void> >::dispatch (this=0x561eac00c330, 
    message=std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> >> (use count 7, weak count 0) = {...}, message_info=...) at /opt/ros/dashing/include/rclcpp/any_subscription_callback.hpp:163
ros2/message_filters#10 0x00007f6958d17f41 in rclcpp::Subscription<sensor_msgs::msg::LaserScan_<std::allocator<void> >, std::allocator<void> >::handle_message (this=0x561eac00c2a0, message=..., message_info=...)
    at /opt/ros/dashing/include/rclcpp/subscription.hpp:146
ros2/message_filters#11 0x00007f695850129f in rclcpp::executor::Executor::execute_subscription(std::shared_ptr<rclcpp::SubscriptionBase>) () from /opt/ros/dashing/lib/librclcpp.so
ros2/message_filters#12 0x00007f69585022e5 in rclcpp::executor::Executor::execute_any_executable(rclcpp::executor::AnyExecutable&) () from /opt/ros/dashing/lib/librclcpp.so
ros2/message_filters#13 0x00007f69585091af in rclcpp::executors::SingleThreadedExecutor::spin() () from /opt/ros/dashing/lib/librclcpp.so
ros2/message_filters#14 0x00007f6958505ea2 in rclcpp::spin(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>) () from /opt/ros/dashing/lib/librclcpp.so
ros2/message_filters#15 0x0000561eabb25ef6 in main (argc=<optimized out>, argv=<optimized out>) at /
@wjwwood
Copy link
Member

wjwwood commented Jan 2, 2020

@cottsay can you triage this issue?

@cottsay cottsay transferred this issue from ros2/message_filters Jan 10, 2020
@cottsay
Copy link
Member

cottsay commented Jan 10, 2020

@jacobperron, you changed the faulting code pretty heavily in Eloquent (#121). The bit that is breaking was removed here: 046df60#diff-724ff79b0edd5a83f8a62b5e2ffa085cL378

Since you have context in this space, do you think this bug was fixed by your change? Could the relevant part of that change be backported to resolve the segfault?

@cottsay cottsay added the bug Something isn't working label Jan 10, 2020
@dirk-thomas
Copy link
Member

@maxlein Please provide exact steps to reproduce the problem.

@jacobperron
Copy link
Member

jacobperron commented Jan 11, 2020

@cottsay I don't think backporting #121 directly is an option since it changes adds API (breaks ABI). But it might be good to know if it does resolve the issue.

@maxlein Are you able to try ROS Eloquent and see if the issue persists?

@maxlein
Copy link
Author

maxlein commented Jan 19, 2020

I am running eloquent now. Exactly this segfault I am not seeing anymore.
But I got another one 😢
This time some signalFailure...
Can't give you more than that, was a situation where we had not much time.

bt#0  std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >::basic_string (__str=..., this=0x7ffc52a4d050) at /usr/include/c++/7/bits/basic_string.h:440
440           { _M_construct(__str._M_data(), __str._M_data() + __str.length()); }
[Current thread is 1 (Thread 0x7facd93b0f40 (LWP 21957))]
(gdb) bt
#0  std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >::basic_string (__str=..., this=0x7ffc52a4d050) at /usr/include/c++/7/bits/basic_string.h:440
#1  message_filters::message_traits::FrameId<sensor_msgs::msg::LaserScan_<std::allocator<void> >, void>::value[abi:cxx11](sensor_msgs::msg::LaserScan_<std::allocator<void> > const&) (m=...)
    at /opt/ros/eloquent/include/message_filters/message_traits.h:67
#2  tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> >, tf2_ros::Buffer>::signalFailure (this=this@entry=0x55a838d5b310, evt=..., reason=reason@entry=tf2_ros::filter_failure_reasons::Unknown)
    at /opt/ros/eloquent/include/tf2_ros/message_filter.h:683
#3  0x00007facd8cc459b in tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> >, tf2_ros::Buffer>::messageDropped (reason=tf2_ros::filter_failure_reasons::Unknown, evt=..., this=0x55a838d5b310)
    at /opt/ros/eloquent/include/tf2_ros/message_filter.h:660
#4  tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> >, tf2_ros::Buffer>::add (this=0x55a838d5b310, evt=...) at /opt/ros/eloquent/include/tf2_ros/message_filter.h:426
#5  0x00007facd8cbeaac in std::function<void (message_filters::MessageEvent<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&)>::operator()(message_filters::MessageEvent<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&) const (__args#0=..., this=0x55a838d5f328) at /usr/include/c++/7/bits/std_function.h:706
#6  message_filters::CallbackHelper1T<message_filters::MessageEvent<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&, sensor_msgs::msg::LaserScan_<std::allocator<void> > >::call (this=0x55a838d5f320, 
    event=..., nonconst_force_copy=<optimized out>) at /opt/ros/eloquent/include/message_filters/signal1.h:74
#7  0x00007facd8cbc990 in message_filters::Signal1<sensor_msgs::msg::LaserScan_<std::allocator<void> > >::call (event=..., this=0x55a838fff4e8) at /opt/ros/eloquent/include/message_filters/signal1.h:117
#8  message_filters::SimpleFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> > >::signalMessage (event=..., this=0x55a838fff4e8) at /opt/ros/eloquent/include/message_filters/simple_filter.h:133
#9  message_filters::Subscriber<sensor_msgs::msg::LaserScan_<std::allocator<void> > >::cb (e=..., this=0x55a838fff4e0) at /opt/ros/eloquent/include/message_filters/subscriber.h:235
#10 message_filters::Subscriber<sensor_msgs::msg::LaserScan_<std::allocator<void> > >::subscribe(rclcpp::Node*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rmw_qos_profile_t)::{lambda(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>)#1}::operator()(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>) const (msg=..., __closure=<optimized out>)
    at /opt/ros/eloquent/include/message_filters/subscriber.h:174
#11 std::_Function_handler<void (std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>), message_filters::Subscriber<sensor_msgs::msg::LaserScan_<std::allocator<void> > >::subscribe(rclcpp::Node*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rmw_qos_profile_t)::{lambda(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>)#1}>::_M_invoke(std::_Any_data const&, std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>&&) (__functor=..., __args#0=...) at /usr/include/c++/7/bits/std_function.h:316
#12 0x00007facd8ceadf2 in std::function<void (std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>)>::operator()(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>) const (
    __args#0=std::shared_ptr<const sensor_msgs::msg::LaserScan_<std::allocator<void> >> (use count 1549966080, weak count -2111918077) = {...}, this=0x55a838fffc98) at /usr/include/c++/7/bits/std_function.h:706
#13 rclcpp::AnySubscriptionCallback<sensor_msgs::msg::LaserScan_<std::allocator<void> >, std::allocator<void> >::dispatch (this=0x55a838fffc58, 
    message=std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> >> (use count 7, weak count 0) = {...}, message_info=...) at /opt/ros/eloquent/include/rclcpp/any_subscription_callback.hpp:166
#14 0x00007facd8ceb010 in rclcpp::Subscription<sensor_msgs::msg::LaserScan_<std::allocator<void> >, std::allocator<void>, rclcpp::message_memory_strategy::MessageMemoryStrategy<sensor_msgs::msg::LaserScan_<std::allocator<void> >, std::allocator<void> > >::handle_message (this=0x55a838fffbb0, message=..., message_info=...) at /opt/ros/eloquent/include/rclcpp/subscription.hpp:227
#15 0x00007facd84b7cef in rclcpp::executor::Executor::execute_subscription(std::shared_ptr<rclcpp::SubscriptionBase>) () from /opt/ros/eloquent/lib/librclcpp.so
#16 0x00007facd84b9015 in rclcpp::executor::Executor::execute_any_executable(rclcpp::executor::AnyExecutable&) () from /opt/ros/eloquent/lib/librclcpp.so
#17 0x00007facd84bf6ef in rclcpp::executors::SingleThreadedExecutor::spin() () from /opt/ros/eloquent/lib/librclcpp.so
#18 0x00007facd84bc3e2 in rclcpp::spin(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>) () from /opt/ros/eloquent/lib/librclcpp.so
#19 0x000055a837d66f99 in main (argc=<optimized out>, argv=<optimized out>) at /home/max/ros2_ws/src/mapping/slam_toolbox/src/slam_toolbox_async_node.cpp:48

@maxlein
Copy link
Author

maxlein commented Jan 31, 2020

Seems this is happening when buffer is full.
Then signalFailure() is crashing because the message is NULL.

TF2_ROS_MESSAGEFILTER_DEBUG(
"Removed oldest message because buffer is full, count now %d (frame_id=%s, stamp=%f)",
message_count_,
(mt::FrameId<M>::value(*front.event.getMessage())).c_str(),
mt::TimeStamp<M>::value(*front.event.getMessage()).seconds());
messageDropped(front.event, filter_failure_reasons::Unknown);

@jacobperron
Copy link
Member

Hmm.. glancing at the code, it doesn't look like we're locking access to messages_ everywhere we should be, for example:

messages_.push_back(info);

typename L_MessageInfo::iterator msg_it = messages_.begin();

Just a shot in the dark: Maybe adding locks at these places would resolve the issue, like we do here,

std::unique_lock<std::mutex> lock(messages_mutex_);

@jacobperron
Copy link
Member

I'm not able to reproduce any crashes. I tried playing around with Rviz and the dummy laser scanner (after looking at #485), but everything looks fine on my end. Are you able to reproduce the Rviz crash reliably? And if so, can you try changing the dummy robot code to match your setup to help me reproduce the issue?

@maxlein
Copy link
Author

maxlein commented Jan 31, 2020

Reproducing reliably is a bit of a problem.
If you see messages like message dropped for unknown reason then you are on a good way.

The last times I got this, was with the global planner of nav2 stack. ( We got the error on live system and with gazebo )
In detail the planner_server is crashing. You could set the QoS depth in the costmap from 50 to 1, then the message dropouts will increase and chances for the error are higher.
Maybe its also enough to increase scanner frequency.

@maxlein maxlein changed the title [ROS2 Dashing] Segmentaition fault on laser scan Segmentaition fault on laser scan Feb 3, 2020
@maxlein maxlein changed the title Segmentaition fault on laser scan Segmentation fault on laser scan Feb 3, 2020
@maxlein
Copy link
Author

maxlein commented Feb 3, 2020

I tried with dummy sensors code and I also get a crash:
Just changed laser rate to 100Hz and let it run for about an hour.

#0  __GI_raise (sig=sig@entry=6) at ../sysdeps/unix/sysv/linux/raise.c:51
#1  0x00007fb0cf98c801 in __GI_abort () at abort.c:79
#2  0x00007fb0cf97c39a in __assert_fail_base (fmt=0x7fb0cfb037d8 "%s%s%s:%u: %s%sAssertion `%s' failed.\n%n", assertion=assertion@entry=0x7fb0bf37be95 "(old & HDL_REFCOUNT_MASK) > 0", 
    file=file@entry=0x7fb0bf37bef8 "/tmp/binarydeb/ros-eloquent-cyclonedds-0.1.0/src/core/ddsc/src/dds_handles.c", line=line@entry=475, function=function@entry=0x7fb0bf37c0a0 "dds_handle_unpin_and_drop_ref")
    at assert.c:92
#3  0x00007fb0cf97c412 in __GI___assert_fail (assertion=0x7fb0bf37be95 "(old & HDL_REFCOUNT_MASK) > 0", file=0x7fb0bf37bef8 "/tmp/binarydeb/ros-eloquent-cyclonedds-0.1.0/src/core/ddsc/src/dds_handles.c", line=475, 
    function=0x7fb0bf37c0a0 "dds_handle_unpin_and_drop_ref") at assert.c:101
#4  0x00007fb0bf34baec in dds_handle_unpin_and_drop_ref () from /opt/ros/eloquent/lib/libddsc.so.0
#5  0x00007fb0bf34ca89 in dds_entity_unpin_and_drop_ref () from /opt/ros/eloquent/lib/libddsc.so.0
#6  0x00007fb0bf356bf3 in dds_create_guardcondition () from /opt/ros/eloquent/lib/libddsc.so.0
#7  0x00007fb0bf5bf01e in rmw_create_guard_condition (context=<optimized out>) at ./src/rmw_node.cpp:1852
#8  0x00007fb0cdfe416e in ?? () from /opt/ros/eloquent/lib/librcl.so
#9  0x00007fb0cdff0d1a in rcl_timer_init () from /opt/ros/eloquent/lib/librcl.so
#10 0x00007fb0d04017c5 in rclcpp::TimerBase::TimerBase(std::shared_ptr<rclcpp::Clock>, std::chrono::duration<long, std::ratio<1l, 1000000000l> >, std::shared_ptr<rclcpp::Context>) ()
   from /opt/ros/eloquent/lib/librclcpp.so
#11 0x00007fb07b090781 in rclcpp::GenericTimer<std::function<void ()>, (void*)0>::GenericTimer(std::shared_ptr<rclcpp::Clock>, std::chrono::duration<long, std::ratio<1l, 1000000000l> >, std::function<void ()>&&, std::shared_ptr<rclcpp::Context>) (context=..., callback=..., period=..., clock=..., this=0x7fb0882f5b80) at /usr/include/c++/8/ext/atomicity.h:96
#12 __gnu_cxx::new_allocator<rclcpp::GenericTimer<std::function<void ()>, (void*)0> >::construct<rclcpp::GenericTimer<std::function<void ()>, (void*)0>, std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >, std::function<void ()>, std::shared_ptr<rclcpp::Context> >(rclcpp::GenericTimer<std::function<void ()>, (void*)0>*, std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >&&, std::function<void ()>&&, std::shared_ptr<rclcpp::Context>&&) (__p=0x7fb0882f5b80, this=<optimized out>) at /usr/include/c++/8/ext/new_allocator.h:136
#13 std::allocator_traits<std::allocator<rclcpp::GenericTimer<std::function<void ()>, (void*)0> > >::construct<rclcpp::GenericTimer<std::function<void ()>, (void*)0>, std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >, std::function<void ()>, std::shared_ptr<rclcpp::Context> >(std::allocator<rclcpp::GenericTimer<std::function<void ()>, (void*)0> >&, rclcpp::GenericTimer<std::function<void ()>, (void*)0>*, std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >&&, std::function<void ()>&&, std::shared_ptr<rclcpp::Context>&&) (__p=0x7fb0882f5b80, __a=...)
    at /usr/include/c++/8/bits/alloc_traits.h:475
#14 std::_Sp_counted_ptr_inplace<rclcpp::GenericTimer<std::function<void ()>, (void*)0>, std::allocator<rclcpp::GenericTimer<std::function<void ()>, (void*)0> >, (__gnu_cxx::_Lock_policy)2>::_Sp_counted_ptr_inplace<std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >, std::function<void ()>, std::shared_ptr<rclcpp::Context> >(std::allocator<rclcpp::GenericTimer<std::function<void ()>, (void*)0> >, std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >&&, std::function<void ()>&&, std::shared_ptr<rclcpp::Context>&&) (__a=..., this=0x7fb0882f5b70)
    at /usr/include/c++/8/bits/shared_ptr_base.h:545
#15 std::__shared_count<(__gnu_cxx::_Lock_policy)2>::__shared_count<rclcpp::GenericTimer<std::function<void ()>, (void*)0>, std::allocator<rclcpp::GenericTimer<std::function<void ()>, (void*)0> >, std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >, std::function<void ()>, std::shared_ptr<rclcpp::Context> >(rclcpp::GenericTimer<std::function<void ()>, (void*)0>*&, std::_Sp_alloc_shared_tag<std::allocator<rclcpp::GenericTimer<std::function<void ()>, (void*)0> > >, std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >&&, std::function<void ()>&&, std::shared_ptr<rclcpp::Context>&&)
    (__a=..., __p=<synthetic pointer>: <optimized out>, this=<synthetic pointer>) at /usr/include/c++/8/bits/shared_ptr_base.h:677
#16 std::__shared_ptr<rclcpp::GenericTimer<std::function<void ()>, (void*)0>, (__gnu_cxx::_Lock_policy)2>::__shared_ptr<std::allocator<rclcpp::GenericTimer<std::function<void ()>, (void*)0> >, std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >, std::function<void ()>, std::shared_ptr<rclcpp::Context> >(std::_Sp_alloc_shared_tag<std::allocator<rclcpp::GenericTimer<std::function<void ()>, (void*)0> > >, std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >&&, std::function<void ()>&&, std::shared_ptr<rclcpp::Context>&&) (__tag=..., this=<synthetic pointer>)
    at /usr/include/c++/8/bits/shared_ptr_base.h:1342
#17 std::shared_ptr<rclcpp::GenericTimer<std::function<void ()>, (void*)0> >::shared_ptr<std::allocator<rclcpp::GenericTimer<std::function<void ()>, (void*)0> >, std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >, std::function<void ()>, std::shared_ptr<rclcpp::Context> >(std::_Sp_alloc_shared_tag<std::allocator<rclcpp::GenericTimer<std::function<void ()>, (void*)0> > >, std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >&&, std::function<void ()>&&, std::shared_ptr<rclcpp::Context>&&) (__tag=..., this=<synthetic pointer>) at /usr/include/c++/8/bits/shared_ptr.h:359
#18 std::allocate_shared<rclcpp::GenericTimer<std::function<void ()>, (void*)0>, std::allocator<rclcpp::GenericTimer<std::function<void ()>, (void*)0> >, std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >, std::function<void ()>, std::shared_ptr<rclcpp::Context> >(std::allocator<rclcpp::GenericTimer<std::function<void ()>, (void*)0> > const&, std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >&&, std::function<void ()>&&, std::shared_ptr<rclcpp::Context>&&) (__a=...) at /usr/include/c++/8/bits/shared_ptr.h:706
#19 std::make_shared<rclcpp::GenericTimer<std::function<void ()>, (void*)0>, std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >, std::function<void ()>, std::shared_ptr<rclcpp::Context> >(std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >&&, std::function<void ()>&&, std::shared_ptr<rclcpp::Context>&&) () at /usr/include/c++/8/bits/shared_ptr.h:722
#20 rclcpp::GenericTimer<std::function<void ()>, (void*)0>::make_shared<std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >, std::function<void ()>, std::shared_ptr<rclcpp::Context> >(std::shared_ptr<rclcpp::Clock>&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >&&, std::function<void ()>&&, std::shared_ptr<rclcpp::Context>&&) () at /opt/ros/eloquent/include/rclcpp/timer.hpp:124
#21 rclcpp::create_timer<std::function<void ()> >(rclcpp::node_interfaces::NodeBaseInterface*, rclcpp::node_interfaces::NodeTimersInterface*, std::shared_ptr<rclcpp::Clock>, rclcpp::Duration, std::function<void ()>&&, std::shared_ptr<rclcpp::callback_group::CallbackGroup>) (node_base=<optimized out>, node_timers=0x565040642ba0, clock=warning: RTTI symbol not found for class 'std::_Sp_counted_ptr_inplace<rclcpp::Clock, std::allocator<rclcpp::Clock>, (__gnu_cxx::_Lock_policy)2>'
warning: RTTI symbol not found for class 'std::_Sp_counted_ptr_inplace<rclcpp::Clock, std::allocator<rclcpp::Clock>, (__gnu_cxx::_Lock_policy)2>'
std::shared_ptr<rclcpp::Clock> (use count 65527, weak count 0) = {...}, period=..., callback=..., 
    group=std::shared_ptr<rclcpp::callback_group::CallbackGroup> (empty) = {...}) at /opt/ros/eloquent/include/rclcpp/create_timer.hpp:42
#22 0x00007fb07b08f6b9 in tf2_ros::CreateTimerROS::createTimer(std::shared_ptr<rclcpp::Clock>, std::chrono::duration<long, std::ratio<1l, 1000000000l> > const&, std::function<void (unsigned long const&)>) ()
    at /usr/include/c++/8/ext/atomicity.h:96
#23 0x00007fb07b08b599 in tf2_ros::Buffer::waitForTransform(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, std::chrono::time_point<std::chrono::_V2::system_clock, std::chrono::duration<long, std::ratio<1l, 1000000000l> > > const&, std::chrono::duration<long, std::ratio<1l, 1000000000l> > const&, std::function<void (std::shared_future<geometry_msgs::msg::TransformStamped_<std::allocator<void> > > const&)>) () at /usr/include/c++/8/ext/atomicity.h:96
#24 0x00007fb07c0a55aa in rviz_default_plugins::transformation::TFWrapper::waitForTransform(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, std::chrono::time_point<std::chrono::_V2::system_clock, std::chrono::duration<long, std::ratio<1l, 1000000000l> > > const&, std::chrono::duration<long, std::ratio<1l, 1000000000l> > const&, std::function<void (std::shared_future<geometry_msgs::msg::TransformStamped_<std::allocator<void> > > const&)>) () from /opt/ros/eloquent/lib/librviz_default_plugins.so
#25 0x00007fb07c0a1615 in rviz_default_plugins::transformation::TFFrameTransformer::waitForTransform(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, std::chrono::time_point<std::chrono::_V2::system_clock, std::chrono::duration<long, std::ratio<1l, 1000000000l> > > const&, std::chrono::duration<long, std::ratio<1l---Type <return> to continue, or q <return> to quit---
, 1000000000l> > const&, std::function<void (std::shared_future<geometry_msgs::msg::TransformStamped_<std::allocator<void> > > const&)>) () from /opt/ros/eloquent/lib/librviz_default_plugins.so
#26 0x00007fb07bf03dc9 in tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> >, rviz_common::transformation::FrameTransformer>::add(message_filters::MessageEvent<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&) () from /opt/ros/eloquent/lib/librviz_default_plugins.so
#27 0x00007fb07bf0570c in message_filters::CallbackHelper1T<message_filters::MessageEvent<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&, sensor_msgs::msg::LaserScan_<std::allocator<void> > >::call(message_filters::MessageEvent<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&, bool) () from /opt/ros/eloquent/lib/librviz_default_plugins.so
#28 0x00007fb07bf054c0 in std::_Function_handler<void (std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>), message_filters::Subscriber<sensor_msgs::msg::LaserScan_<std::allocator<void> > >::subscribe(rclcpp::Node*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rmw_qos_profile_t)::{lambda(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>)#1}>::_M_invoke(std::_Any_data const&, std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>&&) () from /opt/ros/eloquent/lib/librviz_default_plugins.so
#29 0x00007fb07befff52 in rclcpp::AnySubscriptionCallback<sensor_msgs::msg::LaserScan_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > >, rmw_message_info_t const&) () from /opt/ros/eloquent/lib/librviz_default_plugins.so
#30 0x00007fb07bf00170 in rclcpp::Subscription<sensor_msgs::msg::LaserScan_<std::allocator<void> >, std::allocator<void>, rclcpp::message_memory_strategy::MessageMemoryStrategy<sensor_msgs::msg::LaserScan_<std::allocator<void> >, std::allocator<void> > >::handle_message(std::shared_ptr<void>&, rmw_message_info_t const&) () from /opt/ros/eloquent/lib/librviz_default_plugins.so
#31 0x00007fb0d0375d1f in rclcpp::executor::Executor::execute_subscription(std::shared_ptr<rclcpp::SubscriptionBase>) () from /opt/ros/eloquent/lib/librclcpp.so
#32 0x00007fb0d0377045 in rclcpp::executor::Executor::execute_any_executable(rclcpp::executor::AnyExecutable&) () from /opt/ros/eloquent/lib/librclcpp.so
#33 0x00007fb0d0379c2e in rclcpp::executor::Executor::spin_some(std::chrono::duration<long, std::ratio<1l, 1000000000l> >) () from /opt/ros/eloquent/lib/librclcpp.so
#34 0x00007fb0d193978f in rviz_common::VisualizationManager::onUpdate() () from /opt/ros/eloquent/lib/librviz_common.so
#35 0x00007fb0d0b06645 in QMetaObject::activate(QObject*, int, int, void**) () from /usr/lib/x86_64-linux-gnu/libQt5Core.so.5
#36 0x00007fb0d0b130b7 in QTimer::timeout(QTimer::QPrivateSignal) () from /usr/lib/x86_64-linux-gnu/libQt5Core.so.5
#37 0x00007fb0d0b13418 in QTimer::timerEvent(QTimerEvent*) () from /usr/lib/x86_64-linux-gnu/libQt5Core.so.5
#38 0x00007fb0d0b0716b in QObject::event(QEvent*) () from /usr/lib/x86_64-linux-gnu/libQt5Core.so.5
#39 0x00007fb0d10ec83c in QApplicationPrivate::notify_helper(QObject*, QEvent*) () from /usr/lib/x86_64-linux-gnu/libQt5Widgets.so.5
#40 0x00007fb0d10f4104 in QApplication::notify(QObject*, QEvent*) () from /usr/lib/x86_64-linux-gnu/libQt5Widgets.so.5
#41 0x00007fb0d0ad79c8 in QCoreApplication::notifyInternal2(QObject*, QEvent*) () from /usr/lib/x86_64-linux-gnu/libQt5Core.so.5
#42 0x00007fb0d0b2fe1e in QTimerInfoList::activateTimers() () from /usr/lib/x86_64-linux-gnu/libQt5Core.so.5
#43 0x00007fb0d0b305e1 in ?? () from /usr/lib/x86_64-linux-gnu/libQt5Core.so.5
#44 0x00007fb0cbad1417 in g_main_context_dispatch () from /usr/lib/x86_64-linux-gnu/libglib-2.0.so.0
#45 0x00007fb0cbad1650 in ?? () from /usr/lib/x86_64-linux-gnu/libglib-2.0.so.0
#46 0x00007fb0cbad16dc in g_main_context_iteration () from /usr/lib/x86_64-linux-gnu/libglib-2.0.so.0
#47 0x00007fb0d0b3097f in QEventDispatcherGlib::processEvents(QFlags<QEventLoop::ProcessEventsFlag>) () from /usr/lib/x86_64-linux-gnu/libQt5Core.so.5
#48 0x00007fb0d0ad59fa in QEventLoop::exec(QFlags<QEventLoop::ProcessEventsFlag>) () from /usr/lib/x86_64-linux-gnu/libQt5Core.so.5

@maxlein
Copy link
Author

maxlein commented Feb 6, 2020

Any news on this?

@jacobperron
Copy link
Member

I ran a modified dummy sensors laser publisher and RViz all night and didn't see a crash. I did see many "message dropped" logs. I had compiled with debug symbols. I'll try again without them.

@maxlein
Copy link
Author

maxlein commented Feb 6, 2020

Seems I didn‘t write that I tried with eloquent deb package and branch sources.
But from what I saw, the affecting parts are same.
And cyclonedds.
If I can help you somehow, just tell me.

@jacobperron
Copy link
Member

I've also tried eloquent debs, but using the default rmw implementation (Fast-RTPS), still no segfault. Is it also happening with Fast-RTPS too?

When you run RViz, can you see the laser scans or are they not rendering?

@clalancette
Copy link
Contributor

@maxlein I believe that this was resolved with the merging of #279 . Is there any chance you can test out the latest code on master and see if it is now fixed for you? Thanks.

@clalancette
Copy link
Contributor

I believe that this is solved in the latest code, so I'm going to go ahead and close this. Feel free to reopen if you run into this again.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working
Projects
None yet
Development

No branches or pull requests

6 participants