Skip to content

Commit

Permalink
Add locking to protect the TimeSource::NodeState::node_base_ (#2320)
Browse files Browse the repository at this point in the history
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 <clalancette@gmail.com>
  • Loading branch information
clalancette committed Oct 3, 2023
1 parent 7c1143d commit 623c3eb
Showing 1 changed file with 12 additions and 5 deletions.
17 changes: 12 additions & 5 deletions rclcpp/src/rclcpp/time_source.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::mutex> guard(node_base_lock_);
node_base_ = node_base_interface;
node_topics_ = node_topics_interface;
node_graph_ = node_graph_interface;
Expand Down Expand Up @@ -280,17 +281,14 @@ class TimeSource::NodeState final
parameter_subscription_ = rclcpp::AsyncParametersClient::on_parameter_event(
node_topics_,
[this](std::shared_ptr<const rcl_interfaces::msg::ParameterEvent> 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<std::mutex> 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();
Expand Down Expand Up @@ -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};
Expand Down Expand Up @@ -464,6 +463,14 @@ class TimeSource::NodeState final
// Callback for parameter updates
void on_parameter_event(std::shared_ptr<const rcl_interfaces::msg::ParameterEvent> event)
{
std::lock_guard<std::mutex> 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;
Expand Down

0 comments on commit 623c3eb

Please sign in to comment.