Skip to content

Commit 819de9e

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 shutdown path contends on clock_sub_lock_, this produces a deadlock. Fix: move the thread into a local variable under the lock, release the lock, then join outside the critical section. The thread is not dangling — it is unconditionally joined before the function returns. Key improvement over the naive move approach: the subscription is kept alive until after join completes, ensuring the executor thread can finish any in-flight callback without accessing a destroyed subscription. Cleanup order: cancel → (release lock) → join → remove_callback_group → (reacquire lock) → reset subscription. Fixes #2962 Signed-off-by: Pavel Guzenfeld <pavelguzenfeld@gmail.com>
1 parent a525a24 commit 819de9e

1 file changed

Lines changed: 28 additions & 6 deletions

File tree

rclcpp/src/rclcpp/time_source.cpp

Lines changed: 28 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -422,13 +422,35 @@ class TimeSource::NodeState final
422422
// Destroy the subscription for the clock topic
423423
void destroy_clock_sub()
424424
{
425-
std::lock_guard<std::mutex> guard(clock_sub_lock_);
426-
if (clock_executor_thread_.joinable()) {
427-
clock_executor_->cancel();
428-
clock_executor_thread_.join();
429-
clock_executor_->remove_callback_group(clock_callback_group_);
425+
std::thread thread_to_join;
426+
rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_to_clean;
427+
rclcpp::CallbackGroup::SharedPtr cbg_to_remove;
428+
429+
{
430+
std::lock_guard<std::mutex> guard(clock_sub_lock_);
431+
if (clock_executor_thread_.joinable()) {
432+
clock_executor_->cancel();
433+
// Move the thread out so we can join without holding clock_sub_lock_.
434+
// Holding the lock during join() can deadlock if the executor thread's
435+
// shutdown path contends on clock_sub_lock_ (see ros2/rclcpp#2962).
436+
// The thread is unconditionally joined below — it is not dangling.
437+
thread_to_join = std::move(clock_executor_thread_);
438+
executor_to_clean = clock_executor_;
439+
cbg_to_remove = clock_callback_group_;
440+
}
441+
}
442+
443+
// Join outside the lock. The subscription is intentionally kept alive
444+
// until after join so the executor thread can finish any in-flight callback.
445+
if (thread_to_join.joinable()) {
446+
thread_to_join.join();
447+
executor_to_clean->remove_callback_group(cbg_to_remove);
448+
}
449+
450+
{
451+
std::lock_guard<std::mutex> guard(clock_sub_lock_);
452+
clock_subscription_.reset();
430453
}
431-
clock_subscription_.reset();
432454
}
433455

434456
// On set Parameters callback handle

0 commit comments

Comments
 (0)