Skip to content

SIGSEGV at set_clock #1266

@daisukes

Description

@daisukes

Bug report

Required Info:

  • Operating System:
    • Ubuntu 20.04
  • Installation type:
    • Foxy release src build
  • Version or commit hash:
    • rclcpp 2.0.2
  • DDS implementation:
    • Fast-DDS v2.0.1
  • Client library (if applicable):
    • Navigation2

Steps to reproduce issue

It is hard to reproduce the problem intentionally but happens in some nodes randomly.
Here is the backtrace.

#0  0x0000000000000031 in ?? ()
#1  0x00007efd1b6ae1f0 in rcl_clock_call_callbacks () from /opt/ros/foxy/rcl/lib/librcl.so
#2  0x00007efd1b6ae5ef in rcl_set_ros_time_override () from /opt/ros/foxy/rcl/lib/librcl.so
#3  0x00007efd1be8a729 in rclcpp::TimeSource::set_clock(std::shared_ptr<builtin_interfaces::msg::Time_<std::allocator<void> > >, bool, std::shared_ptr<rclcpp::Clock>) () from /opt/ros/foxy/rclcpp/lib/librclcpp.so
#4  0x00007efd1be8a96d in rclcpp::TimeSource::clock_cb(std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > >) () from /opt/ros/foxy/rclcpp/lib/librclcpp.so
#5  0x00007efd1bea591e in void std::__invoke_impl<void, void (rclcpp::TimeSource::*&)(std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > >), rclcpp::TimeSource*&, std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > > >(std::__invoke_memfun_deref, void (rclcpp::TimeSource::*&)(std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > >), rclcpp::TimeSource*&, std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > >&&) () from /opt/ros/foxy/rclcpp/lib/librclcpp.so
#6  0x00007efd1bea3a0a in std::__invoke_result<void (rclcpp::TimeSource::*&)(std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > >), rclcpp::TimeSource*&, std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > > >::type std::__invoke<void (rclcpp::TimeSource::*&)(std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > >), rclcpp::TimeSource*&, std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > > >(void (rclcpp::TimeSource::*&)(std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > >), rclcpp::TimeSource*&, std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > >&&) () from /opt/ros/foxy/rclcpp/lib/librclcpp.so
#7  0x00007efd1bea1a64 in void std::_Bind<void (rclcpp::TimeSource::*(rclcpp::TimeSource*, std::_Placeholder<1>))(std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > >)>::__call<void, std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > >&&, 0ul, 1ul>(std::tuple<std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > >&&>&&, std::_Index_tuple<0ul, 1ul>) ()
   from /opt/ros/foxy/rclcpp/lib/librclcpp.so
#8  0x00007efd1be9fbae in void std::_Bind<void (rclcpp::TimeSource::*(rclcpp::TimeSource*, std::_Placeholder<1>))(std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > >)>::operator()<std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > >, void>(std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > >&&) () from /opt/ros/foxy/rclcpp/lib/librclcpp.so
#9  0x00007efd1be9da89 in std::_Function_handler<void (std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > >), std::_Bind<void (rclcpp::TimeSource::*(rclcpp::TimeSource*, std::_Placeholder<1>))(std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > >)> >::_M_invoke(std::_Any_data const&, std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > >&&) ()
   from /opt/ros/foxy/rclcpp/lib/librclcpp.so
#10 0x00007efd1bed378b in std::function<void (std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > >)>::operator()(std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > >) const () from /opt/ros/foxy/rclcpp/lib/librclcpp.so
#11 0x00007efd1bed0ea7 in rclcpp::AnySubscriptionCallback<rosgraph_msgs::msg::Clock_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<rosgraph_msgs::msg::Clock_<std::allocator<void> > >, rclcpp::MessageInfo const&) () from /opt/ros/foxy/rclcpp/lib/librclcpp.so
#12 0x00007efd1becdf02 in rclcpp::Subscription<rosgraph_msgs::msg::Clock_<std::allocator<void> >, std::allocator<void>, rclcpp::message_memory_strategy::MessageMemoryStrategy<rosgraph_msgs::msg::Clock_<std::allocator<void> >, std::allocator<void> > >::handle_message(std::shared_ptr<void>&, rclcpp::MessageInfo const&) () from /opt/ros/foxy/rclcpp/lib/librclcpp.so
#13 0x00007efd1bd78b46 in rclcpp::Executor::execute_subscription(std::shared_ptr<rclcpp::SubscriptionBase>)::{lambda()#6}::operator()() const () from /opt/ros/foxy/rclcpp/lib/librclcpp.so
#14 0x00007efd1bd7b9bd in std::_Function_handler<void (), rclcpp::Executor::execute_subscription(std::shared_ptr<rclcpp::SubscriptionBase>)::{lambda()#6}>::_M_invoke(std::_Any_data const&) () from /opt/ros/foxy/rclcpp/lib/librclcpp.so
#15 0x00007efd1bd5c1b4 in std::function<void ()>::operator()() const () from /opt/ros/foxy/rclcpp/lib/librclcpp.so
#16 0x00007efd1bd781f8 in take_and_do_error_handling(char const*, char const*, std::function<bool ()>, std::function<void ()>) () from /opt/ros/foxy/rclcpp/lib/librclcpp.so
#17 0x00007efd1bd79216 in rclcpp::Executor::execute_subscription(std::shared_ptr<rclcpp::SubscriptionBase>) () from /opt/ros/foxy/rclcpp/lib/librclcpp.so
#18 0x00007efd1bd77f45 in rclcpp::Executor::execute_any_executable(rclcpp::AnyExecutable&) () from /opt/ros/foxy/rclcpp/lib/librclcpp.so
#19 0x00007efd1bd8595c in rclcpp::executors::SingleThreadedExecutor::spin() () from /opt/ros/foxy/rclcpp/lib/librclcpp.so
#20 0x00007efd1b512b4d in std::thread::_State_impl<std::thread::_Invoker<std::tuple<nav2_util::NodeThread::NodeThread(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>)::{lambda()#1}> > >::_M_run() () from /opt/overlay_ws/install/nav2_util/lib/libnav2_util_core.so
#21 0x00007efd1b217cb4 in ?? () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#22 0x00007efd1b32b609 in start_thread (arg=<optimized out>) at pthread_create.c:477
#23 0x00007efd1af05103 in clone () from /usr/lib/x86_64-linux-gnu/libc.so.6

bug fix

I think the clock needs to be locked before calling rcl_set_ros_time_override which eventually access jump_callbacks array.
I have executed my simulation overnight with the fixed code and so far it looks good.
daisukes@4a2579f

Also, I think these two lines should have a lock because it could call the same function.

auto ret = rcl_enable_ros_time_override(clock->get_clock_handle());

auto ret = rcl_disable_ros_time_override(clock->get_clock_handle());

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions