diff --git a/rclcpp/include/rclcpp/node.hpp b/rclcpp/include/rclcpp/node.hpp index cdf3084c07..7e5f402f8a 100644 --- a/rclcpp/include/rclcpp/node.hpp +++ b/rclcpp/include/rclcpp/node.hpp @@ -148,11 +148,6 @@ class Node : public std::enable_shared_from_this 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 & - 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 diff --git a/rclcpp/include/rclcpp/node_interfaces/node_base.hpp b/rclcpp/include/rclcpp/node_interfaces/node_base.hpp index e8af3bed54..8a19a6c9df 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_base.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_base.hpp @@ -98,10 +98,6 @@ class NodeBase : public NodeBaseInterface bool callback_group_in_node(rclcpp::CallbackGroup::SharedPtr group) override; - RCLCPP_PUBLIC - const std::vector & - 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 diff --git a/rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp b/rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp index 8b5a75aa03..ebe7b1b98e 100644 --- a/rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp +++ b/rclcpp/include/rclcpp/node_interfaces/node_base_interface.hpp @@ -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 & - get_callback_groups() const = 0; - using CallbackGroupFunction = std::function; /// Iterate over the stored callback groups, calling the given function on each valid one. diff --git a/rclcpp/src/rclcpp/node.cpp b/rclcpp/src/rclcpp/node.cpp index 39e7bca139..c9ed1e3ac2 100644 --- a/rclcpp/src/rclcpp/node.cpp +++ b/rclcpp/src/rclcpp/node.cpp @@ -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 & -Node::get_callback_groups() const -{ - return node_base_->get_callback_groups(); -} - void Node::for_each_callback_group( const node_interfaces::NodeBaseInterface::CallbackGroupFunction & func) diff --git a/rclcpp/src/rclcpp/node_interfaces/node_base.cpp b/rclcpp/src/rclcpp/node_interfaces/node_base.cpp index 98c28cbc23..5240c8c818 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_base.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_base.cpp @@ -248,12 +248,6 @@ NodeBase::callback_group_in_node(rclcpp::CallbackGroup::SharedPtr group) return false; } -const std::vector & -NodeBase::get_callback_groups() const -{ - return callback_groups_; -} - void NodeBase::for_each_callback_group(const CallbackGroupFunction & func) { std::lock_guard lock(callback_groups_mutex_); diff --git a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp index 1474765913..028afe4be5 100644 --- a/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp +++ b/rclcpp_lifecycle/include/rclcpp_lifecycle/lifecycle_node.hpp @@ -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 & - get_callback_groups() const; - /// Iterate over the callback groups in the node, calling func on each valid one. RCLCPP_PUBLIC void diff --git a/rclcpp_lifecycle/src/lifecycle_node.cpp b/rclcpp_lifecycle/src/lifecycle_node.cpp index 0d7eb9d592..d2bd49bcf7 100644 --- a/rclcpp_lifecycle/src/lifecycle_node.cpp +++ b/rclcpp_lifecycle/src/lifecycle_node.cpp @@ -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 & -LifecycleNode::get_callback_groups() const -{ - return node_base_->get_callback_groups(); -} - void LifecycleNode::for_each_callback_group( const rclcpp::node_interfaces::NodeBaseInterface::CallbackGroupFunction & func)