-
Notifications
You must be signed in to change notification settings - Fork 522
Closed
Labels
bugSomething isn't workingSomething isn't working
Description
Bug report
Required Info:
- Operating System: Ubuntu 24.04
- Installation type: debian binaries
- Version:
- ros-jazzy-rclcpp Version: 28.1.5-1noble.20240922.085057
- ros-rolling-rclcpp Version: 28.3.3-1noble.20240919.221549
- DDS implementation: Fast-RTPS
- Client library: rclcpp
Issue description
The rclcpp::Executor crashes when a timer with a non-default callback group is destroyed before the executor stops spinning.
The bug also appears if a callback group is created and destroyed without being added to the timer.
The bug does not manifest in the example below when:
- The timer's callback group has a longer lifetime than the executor spin thread (e.g. declared in the outer scope).
- The timer uses the default callback group.
- The callback group is moved to the timer factory.
Steps to reproduce issue
See the full gist
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/string.hpp>
using namespace std::chrono_literals;
int main(int argc, char** argv) {
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("test");
auto log = node->get_logger();
rclcpp::executors::SingleThreadedExecutor executor;
auto spinThread = std::thread([&] {
executor.add_node(node);
executor.spin();
executor.remove_node(node);
});
while (!executor.is_spinning()) {
std::this_thread::sleep_for(1ms);
}
{
RCLCPP_INFO(log, "BEGIN");
auto cg = node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
auto timer = node->create_timer(1s, [&log] { RCLCPP_INFO(log, "timer"); }, cg); // SIGSEGV
// auto timer = node->create_timer(1s, [&log] { RCLCPP_INFO(log, "timer"); }, std::move(cg)); // OK
std::this_thread::sleep_for(100ms); // wait a bit for the executor to catch up
RCLCPP_INFO(log, "END"); // timer and cg go out of scope here
}
executor.cancel();
if (spinThread.joinable()) {
spinThread.join();
}
rclcpp::shutdown();
}Expected behavior
The node runs and terminates without issue.
Actual behavior
The node fails with a Segmentation fault in rclcpp::Executor::spin().
Additional information
Backtrace:
Thread 16 "rclcpp_bug" received signal SIGSEGV, Segmentation fault.
[Switching to Thread 0x7fffe90006c0 (LWP 66063)]
0x00007ffff72fd301 in rmw_fastrtps_shared_cpp::__rmw_wait(char const*, rmw_subscriptions_s*, rmw_guard_conditions_s*, rmw_services_s*, rmw_clients_s*, rmw_events_s*, rmw_wait_set_s*, rmw_time_s const*) ()
from /opt/ros/jazzy/lib/librmw_fastrtps_shared_cpp.so
(gdb) bt
#0 0x00007ffff72fd301 in rmw_fastrtps_shared_cpp::__rmw_wait(char const*, rmw_subscriptions_s*, rmw_guard_conditions_s*, rmw_services_s*, rmw_clients_s*, rmw_events_s*, rmw_wait_set_s*, rmw_time_s const*) ()
from /opt/ros/jazzy/lib/librmw_fastrtps_shared_cpp.so
#1 0x00007ffff735d8f8 in rmw_wait () from /opt/ros/jazzy/lib/librmw_fastrtps_cpp.so
#2 0x00007ffff7f6622c in rcl_wait () from /opt/ros/jazzy/lib/librcl.so
#3 0x00007ffff7de565f in ?? () from /opt/ros/jazzy/lib/librclcpp.so
#4 0x00007ffff7d08e00 in rclcpp::Executor::wait_for_work(std::chrono::duration<long, std::ratio<1l, 1000000000l> >) () from /opt/ros/jazzy/lib/librclcpp.so
#5 0x00007ffff7d0962b in rclcpp::Executor::get_next_executable(rclcpp::AnyExecutable&, std::chrono::duration<long, std::ratio<1l, 1000000000l> >) () from /opt/ros/jazzy/lib/librclcpp.so
#6 0x00007ffff7d193a5 in rclcpp::executors::SingleThreadedExecutor::spin() () from /opt/ros/jazzy/lib/librclcpp.so
#7 0x0000555555703dc1 in operator() (__closure=0x555555b6e0a8) at /home/mspieler/work/brahma_ws/ros2_ws/src/rclcpp_bug/bug.cpp:16
#8 0x000055555570c934 in std::__invoke_impl<void, main(int, char**)::<lambda()> >(std::__invoke_other, struct {...} &&) (__f=...) at /usr/include/c++/13/bits/invoke.h:61
#9 0x000055555570c8f7 in std::__invoke<main(int, char**)::<lambda()> >(struct {...} &&) (__fn=...) at /usr/include/c++/13/bits/invoke.h:96
#10 0x000055555570c8a4 in std::thread::_Invoker<std::tuple<main(int, char**)::<lambda()> > >::_M_invoke<0>(std::_Index_tuple<0>) (this=0x555555b6e0a8) at /usr/include/c++/13/bits/std_thread.h:292
#11 0x000055555570c7ee in std::thread::_Invoker<std::tuple<main(int, char**)::<lambda()> > >::operator()(void) (this=0x555555b6e0a8) at /usr/include/c++/13/bits/std_thread.h:299
#12 0x000055555570c4f0 in std::thread::_State_impl<std::thread::_Invoker<std::tuple<main(int, char**)::<lambda()> > > >::_M_run(void) (this=0x555555b6e0a0) at /usr/include/c++/13/bits/std_thread.h:244
#13 0x00007ffff78ecdb4 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#14 0x00007ffff749ca94 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:447
#15 0x00007ffff7529c3c in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:78
Reactions are currently unavailable
Metadata
Metadata
Assignees
Labels
bugSomething isn't workingSomething isn't working