Skip to content

Commit

Permalink
Remove unsafe get_callback_groups API.
Browse files Browse the repository at this point in the history
Callers should change to using for_each_callback_group(), or
store the callback groups they need internally.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>
  • Loading branch information
clalancette committed Jul 23, 2021
1 parent cc7b2bc commit 9ff1acf
Show file tree
Hide file tree
Showing 7 changed files with 0 additions and 41 deletions.
5 changes: 0 additions & 5 deletions rclcpp/include/rclcpp/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,11 +148,6 @@ class Node : public std::enable_shared_from_this<Node>
rclcpp::CallbackGroupType group_type,
bool automatically_add_to_executor_with_node = true);

/// Return the list of callback groups in the node.
RCLCPP_PUBLIC
const std::vector<rclcpp::CallbackGroup::WeakPtr> &
get_callback_groups() const;

/// Iterate over the callback groups in the node, calling the given function on each valid one.
/**
* This method is called in a thread-safe way, and also makes sure to only call the given
Expand Down
4 changes: 0 additions & 4 deletions rclcpp/include/rclcpp/node_interfaces/node_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,10 +98,6 @@ class NodeBase : public NodeBaseInterface
bool
callback_group_in_node(rclcpp::CallbackGroup::SharedPtr group) override;

RCLCPP_PUBLIC
const std::vector<rclcpp::CallbackGroup::WeakPtr> &
get_callback_groups() const override;

/// Iterate over the stored callback groups, calling the given function on each valid one.
/**
* This method is called in a thread-safe way, and also makes sure to only call the given
Expand Down
6 changes: 0 additions & 6 deletions rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,12 +122,6 @@ class NodeBaseInterface
bool
callback_group_in_node(rclcpp::CallbackGroup::SharedPtr group) = 0;

/// Return list of callback groups associated with this node.
RCLCPP_PUBLIC
virtual
const std::vector<rclcpp::CallbackGroup::WeakPtr> &
get_callback_groups() const = 0;

using CallbackGroupFunction = std::function<void (rclcpp::CallbackGroup::SharedPtr)>;

/// Iterate over the stored callback groups, calling the given function on each valid one.
Expand Down
6 changes: 0 additions & 6 deletions rclcpp/src/rclcpp/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -482,12 +482,6 @@ Node::get_subscriptions_info_by_topic(const std::string & topic_name, bool no_ma
return node_graph_->get_subscriptions_info_by_topic(topic_name, no_mangle);
}

const std::vector<rclcpp::CallbackGroup::WeakPtr> &
Node::get_callback_groups() const
{
return node_base_->get_callback_groups();
}

void
Node::for_each_callback_group(
const node_interfaces::NodeBaseInterface::CallbackGroupFunction & func)
Expand Down
6 changes: 0 additions & 6 deletions rclcpp/src/rclcpp/node_interfaces/node_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -248,12 +248,6 @@ NodeBase::callback_group_in_node(rclcpp::CallbackGroup::SharedPtr group)
return false;
}

const std::vector<rclcpp::CallbackGroup::WeakPtr> &
NodeBase::get_callback_groups() const
{
return callback_groups_;
}

void NodeBase::for_each_callback_group(const CallbackGroupFunction & func)
{
std::lock_guard<std::mutex> lock(callback_groups_mutex_);
Expand Down
8 changes: 0 additions & 8 deletions rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -192,14 +192,6 @@ class LifecycleNode : public node_interfaces::LifecycleNodeInterface,
rclcpp::CallbackGroupType group_type,
bool automatically_add_to_executor_with_node = true);

/// Return the list of callback groups in the node.
/**
* \return list of callback groups in the node.
*/
RCLCPP_LIFECYCLE_PUBLIC
const std::vector<rclcpp::CallbackGroup::WeakPtr> &
get_callback_groups() const;

/// Iterate over the callback groups in the node, calling func on each valid one.
RCLCPP_PUBLIC
void
Expand Down
6 changes: 0 additions & 6 deletions rclcpp_lifecycle/src/lifecycle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -365,12 +365,6 @@ LifecycleNode::get_subscriptions_info_by_topic(const std::string & topic_name, b
return node_graph_->get_subscriptions_info_by_topic(topic_name, no_mangle);
}

const std::vector<rclcpp::CallbackGroup::WeakPtr> &
LifecycleNode::get_callback_groups() const
{
return node_base_->get_callback_groups();
}

void
LifecycleNode::for_each_callback_group(
const rclcpp::node_interfaces::NodeBaseInterface::CallbackGroupFunction & func)
Expand Down

0 comments on commit 9ff1acf

Please sign in to comment.