diff --git a/foros/include/akit/failover/foros/cluster_node.hpp b/foros/include/akit/failover/foros/cluster_node.hpp index 4dd8f5e..0fbc6ee 100644 --- a/foros/include/akit/failover/foros/cluster_node.hpp +++ b/foros/include/akit/failover/foros/cluster_node.hpp @@ -135,13 +135,18 @@ class ClusterNode : 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. + /// Iterate over the callback groups in the node, calling func on each valid + /// one. /** - * \return List of callback groups in the node. + * From Humble, get_callback_groups() is replaced with this method. + * https://github.com/ros2/rclcpp/pull/1723 + * + * \param[in] func The callback function to call on each valid callback group. */ CLUSTER_NODE_PUBLIC - const std::vector &get_callback_groups() - const; + void for_each_callback_group( + const rclcpp::node_interfaces::NodeBaseInterface::CallbackGroupFunction + &func); /// Create a Publisher. /** diff --git a/foros/include/akit/failover/foros/cluster_node_publisher.hpp b/foros/include/akit/failover/foros/cluster_node_publisher.hpp index 2a9a7e5..fd0aee6 100644 --- a/foros/include/akit/failover/foros/cluster_node_publisher.hpp +++ b/foros/include/akit/failover/foros/cluster_node_publisher.hpp @@ -72,7 +72,7 @@ class ClusterNodePublisher : public rclcpp::Publisher { * * \param[in] msg a message to publish. */ - void publish(std::unique_ptr msg) override { + void publish(std::unique_ptr msg) { if (node_lifecycle_interface_ != nullptr && !node_lifecycle_interface_->is_activated()) { // ignore publish request when publisher is not activated @@ -88,7 +88,7 @@ class ClusterNodePublisher : public rclcpp::Publisher { * * \param[in] msg a message to publish. */ - void publish(const MessageT& msg) override { + void publish(const MessageT& msg) { if (node_lifecycle_interface_ != nullptr && !node_lifecycle_interface_->is_activated()) { // ignore publish request when publisher is not activated diff --git a/foros/src/cluster_node.cpp b/foros/src/cluster_node.cpp index f2dbe9f..ce4ba8d 100644 --- a/foros/src/cluster_node.cpp +++ b/foros/src/cluster_node.cpp @@ -119,9 +119,10 @@ rclcpp::CallbackGroup::SharedPtr ClusterNode::create_callback_group( group_type, automatically_add_to_executor_with_node); } -const std::vector - &ClusterNode::get_callback_groups() const { - return node_base_->get_callback_groups(); +void ClusterNode::for_each_callback_group( + const rclcpp::node_interfaces::NodeBaseInterface::CallbackGroupFunction + &func) { + node_base_->for_each_callback_group(func); } const rclcpp::ParameterValue &ClusterNode::declare_parameter( diff --git a/foros/test/test_raft.hpp b/foros/test/test_raft.hpp index d4c4a88..0c9540d 100644 --- a/foros/test/test_raft.hpp +++ b/foros/test/test_raft.hpp @@ -112,7 +112,7 @@ class TestContext : public akit::failover::foros::raft::Context { request->prev_log_index = prev_log_index; request->prev_log_term = prev_log_term; request->entries = entries; - return append_entries_->async_send_request(request); + return append_entries_->async_send_request(request).future.share(); } private: