From 634bb991209fe1dda13b67a17cceb2f4c693b4d8 Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Tue, 12 Sep 2023 12:33:03 +0000 Subject: [PATCH] Add locking to protect the TimeSource::NodeState::node_base_ We need this because it is possible for one thread to be handling the on_parameter_event callback while another one is detaching the node. This lock will protect that from happening. Signed-off-by: Chris Lalancette --- rclcpp/src/rclcpp/time_source.cpp | 17 ++++++++++++----- 1 file changed, 12 insertions(+), 5 deletions(-) diff --git a/rclcpp/src/rclcpp/time_source.cpp b/rclcpp/src/rclcpp/time_source.cpp index a0e1d00853..465ceaf5a7 100644 --- a/rclcpp/src/rclcpp/time_source.cpp +++ b/rclcpp/src/rclcpp/time_source.cpp @@ -236,6 +236,7 @@ class TimeSource::NodeState final rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface, rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_interface) { + std::lock_guard guard(node_base_lock_); node_base_ = node_base_interface; node_topics_ = node_topics_interface; node_graph_ = node_graph_interface; @@ -280,17 +281,14 @@ class TimeSource::NodeState final parameter_subscription_ = rclcpp::AsyncParametersClient::on_parameter_event( node_topics_, [this](std::shared_ptr event) { - if (node_base_ != nullptr) { - this->on_parameter_event(event); - } - // Do nothing if node_base_ is nullptr because it means the TimeSource is now - // without an attached node + this->on_parameter_event(event); }); } // Detach the attached node void detachNode() { + std::lock_guard guard(node_base_lock_); // destroy_clock_sub() *must* be first here, to ensure that the executor // can't possibly call any of the callbacks as we are cleaning up. destroy_clock_sub(); @@ -327,6 +325,7 @@ class TimeSource::NodeState final std::thread clock_executor_thread_; // Preserve the node reference + std::mutex node_base_lock_; rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_{nullptr}; rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_{nullptr}; rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph_{nullptr}; @@ -464,6 +463,14 @@ class TimeSource::NodeState final // Callback for parameter updates void on_parameter_event(std::shared_ptr event) { + std::lock_guard guard(node_base_lock_); + + if (node_base_ == nullptr) { + // Do nothing if node_base_ is nullptr because it means the TimeSource is now + // without an attached node + return; + } + // Filter out events on 'use_sim_time' parameter instances in other nodes. if (event->node != node_base_->get_fully_qualified_name()) { return;