Skip to content

Commit

Permalink
Fix dangerous std::bind capture in ParameterEventHandler implementati…
Browse files Browse the repository at this point in the history
…on (ros2#1770)

Signed-off-by: Geoffrey Biggs <gbiggs@killbots.net>
  • Loading branch information
gbiggs authored and Alberto Soragna committed Jan 21, 2022
1 parent 21986e7 commit 1bb528a
Show file tree
Hide file tree
Showing 3 changed files with 49 additions and 28 deletions.
40 changes: 30 additions & 10 deletions rclcpp/include/rclcpp/parameter_event_handler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -173,9 +173,13 @@ class ParameterEventHandler
node_base_ = rclcpp::node_interfaces::get_node_base_interface(node);
auto node_topics = rclcpp::node_interfaces::get_node_topics_interface(node);

callbacks_ = std::make_shared<Callbacks>();

event_subscription_ = rclcpp::create_subscription<rcl_interfaces::msg::ParameterEvent>(
node_topics, "/parameter_events", qos,
std::bind(&ParameterEventHandler::event_callback, this, std::placeholders::_1));
[callbacks = callbacks_](const rcl_interfaces::msg::ParameterEvent & event) {
callbacks->event_callback(event);
});
}

using ParameterEventCallbackType =
Expand Down Expand Up @@ -319,18 +323,34 @@ class ParameterEventHandler
};
// *INDENT-ON*

// Map container for registered parameters
std::unordered_map<
std::pair<std::string, std::string>,
CallbacksContainerType,
StringPairHash
> parameter_callbacks_;
struct Callbacks
{
std::recursive_mutex mutex_;

rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr event_subscription_;
// Map container for registered parameters
std::unordered_map<
std::pair<std::string, std::string>,
CallbacksContainerType,
StringPairHash
> parameter_callbacks_;

std::list<ParameterEventCallbackHandle::WeakPtr> event_callbacks_;
std::list<ParameterEventCallbackHandle::WeakPtr> event_callbacks_;

std::recursive_mutex mutex_;
/// Callback for parameter events subscriptions.
RCLCPP_PUBLIC
void
event_callback(const rcl_interfaces::msg::ParameterEvent & event);
};

std::shared_ptr<Callbacks> callbacks_;

// Utility function for resolving node path.
std::string resolve_path(const std::string & path);

// Node interface used for base functionality
std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface> node_base_;

rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr event_subscription_;
};

} // namespace rclcpp
Expand Down
31 changes: 16 additions & 15 deletions rclcpp/src/rclcpp/parameter_event_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,10 +29,10 @@ ParameterEventCallbackHandle::SharedPtr
ParameterEventHandler::add_parameter_event_callback(
ParameterEventCallbackType callback)
{
std::lock_guard<std::recursive_mutex> lock(mutex_);
std::lock_guard<std::recursive_mutex> lock(callbacks_->mutex_);
auto handle = std::make_shared<ParameterEventCallbackHandle>();
handle->callback = callback;
event_callbacks_.emplace_front(handle);
callbacks_->event_callbacks_.emplace_front(handle);

return handle;
}
Expand All @@ -58,13 +58,15 @@ void
ParameterEventHandler::remove_parameter_event_callback(
ParameterEventCallbackHandle::SharedPtr callback_handle)
{
std::lock_guard<std::recursive_mutex> lock(mutex_);
std::lock_guard<std::recursive_mutex> lock(callbacks_->mutex_);
auto it = std::find_if(
event_callbacks_.begin(),
event_callbacks_.end(),
HandleCompare<ParameterEventCallbackHandle>(callback_handle.get()));
if (it != event_callbacks_.end()) {
event_callbacks_.erase(it);
callbacks_->event_callbacks_.begin(),
callbacks_->event_callbacks_.end(),
[callback_handle](const auto & weak_handle) {
return callback_handle.get() == weak_handle.lock().get();
});
if (it != callbacks_->event_callbacks_.end()) {
callbacks_->event_callbacks_.erase(it);
} else {
throw std::runtime_error("Callback doesn't exist");
}
Expand All @@ -76,15 +78,15 @@ ParameterEventHandler::add_parameter_callback(
ParameterCallbackType callback,
const std::string & node_name)
{
std::lock_guard<std::recursive_mutex> lock(mutex_);
std::lock_guard<std::recursive_mutex> lock(callbacks_->mutex_);
auto full_node_name = resolve_path(node_name);

auto handle = std::make_shared<ParameterCallbackHandle>();
handle->callback = callback;
handle->parameter_name = parameter_name;
handle->node_name = full_node_name;
// the last callback registered is executed first.
parameter_callbacks_[{parameter_name, full_node_name}].emplace_front(handle);
callbacks_->parameter_callbacks_[{parameter_name, full_node_name}].emplace_front(handle);

return handle;
}
Expand All @@ -93,17 +95,17 @@ void
ParameterEventHandler::remove_parameter_callback(
ParameterCallbackHandle::SharedPtr callback_handle)
{
std::lock_guard<std::recursive_mutex> lock(mutex_);
std::lock_guard<std::recursive_mutex> lock(callbacks_->mutex_);
auto handle = callback_handle.get();
auto & container = parameter_callbacks_[{handle->parameter_name, handle->node_name}];
auto & container = callbacks_->parameter_callbacks_[{handle->parameter_name, handle->node_name}];
auto it = std::find_if(
container.begin(),
container.end(),
HandleCompare<ParameterCallbackHandle>(handle));
if (it != container.end()) {
container.erase(it);
if (container.empty()) {
parameter_callbacks_.erase({handle->parameter_name, handle->node_name});
callbacks_->parameter_callbacks_.erase({handle->parameter_name, handle->node_name});
}
} else {
throw std::runtime_error("Callback doesn't exist");
Expand Down Expand Up @@ -171,8 +173,7 @@ ParameterEventHandler::get_parameters_from_event(
}

void
ParameterEventHandler::event_callback(
const rcl_interfaces::msg::ParameterEvent::SharedPtr event)
ParameterEventHandler::Callbacks::event_callback(const rcl_interfaces::msg::ParameterEvent & event)
{
std::lock_guard<std::recursive_mutex> lock(mutex_);

Expand Down
6 changes: 3 additions & 3 deletions rclcpp/test/rclcpp/test_parameter_event_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,17 +29,17 @@ class TestParameterEventHandler : public rclcpp::ParameterEventHandler

void test_event(const rcl_interfaces::msg::ParameterEvent::SharedPtr event)
{
event_callback(event);
callbacks_->event_callback(*event);
}

size_t num_event_callbacks()
{
return event_callbacks_.size();
return callbacks_->event_callbacks_.size();
}

size_t num_parameter_callbacks()
{
return parameter_callbacks_.size();
return callbacks_->parameter_callbacks_.size();
}
};

Expand Down

0 comments on commit 1bb528a

Please sign in to comment.