Skip to content

Commit bba7586

Browse files
Fix potential deadlock in TimeSource::destroy_clock_sub
destroy_clock_sub() held clock_sub_lock_ while calling clock_executor_thread_.join(). If the executor thread's callback tried to access state protected by clock_sub_lock_ before exiting, this would deadlock: main thread waits for executor thread to finish, executor thread waits for main thread to release the lock. Fix by moving the thread, executor, and callback group into local variables under the lock, then releasing the lock before joining. This ensures the executor thread can complete its final callback without contending on clock_sub_lock_. Fixes #2962 Signed-off-by: Pavel Guzenfeld <pavelguzenfeld@gmail.com>
1 parent dca23fe commit bba7586

File tree

1 file changed

+24
-7
lines changed

1 file changed

+24
-7
lines changed

rclcpp/src/rclcpp/time_source.cpp

Lines changed: 24 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -409,14 +409,31 @@ class TimeSource::NodeState final
409409
// Destroy the subscription for the clock topic
410410
void destroy_clock_sub()
411411
{
412-
std::lock_guard<std::mutex> guard(clock_sub_lock_);
413-
if (clock_executor_thread_.joinable()) {
414-
cancel_clock_executor_promise_.set_value();
415-
clock_executor_->cancel();
416-
clock_executor_thread_.join();
417-
clock_executor_->remove_callback_group(clock_callback_group_);
412+
std::thread thread_to_join;
413+
std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> executor_to_clean;
414+
rclcpp::CallbackGroup::SharedPtr callback_group_to_remove;
415+
416+
{
417+
std::lock_guard<std::mutex> guard(clock_sub_lock_);
418+
if (clock_executor_thread_.joinable()) {
419+
cancel_clock_executor_promise_.set_value();
420+
clock_executor_->cancel();
421+
// Move thread and executor out of lock scope to avoid holding
422+
// clock_sub_lock_ while joining. The executor thread's callbacks
423+
// may access state protected by clock_sub_lock_, which would
424+
// deadlock if we held it during join().
425+
thread_to_join = std::move(clock_executor_thread_);
426+
executor_to_clean = clock_executor_;
427+
callback_group_to_remove = clock_callback_group_;
428+
}
429+
clock_subscription_.reset();
430+
}
431+
432+
// Join and clean up outside the lock
433+
if (thread_to_join.joinable()) {
434+
thread_to_join.join();
435+
executor_to_clean->remove_callback_group(callback_group_to_remove);
418436
}
419-
clock_subscription_.reset();
420437
}
421438

422439
// Parameter Event subscription

0 commit comments

Comments
 (0)