Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added humble branch #1

Merged
merged 6 commits into from
Oct 17, 2022
Merged
Show file tree
Hide file tree
Changes from 5 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 7 additions & 4 deletions foros/include/akit/failover/foros/cluster_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -135,13 +135,16 @@ class ClusterNode : public std::enable_shared_from_this<ClusterNode>,
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<rclcpp::CallbackGroup::WeakPtr> &get_callback_groups()
const;
void for_each_callback_group(
const rclcpp::node_interfaces::NodeBaseInterface::CallbackGroupFunction & func);

/// Create a Publisher.
/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ class ClusterNodePublisher : public rclcpp::Publisher<MessageT, Alloc> {
*
* \param[in] msg a message to publish.
*/
void publish(std::unique_ptr<MessageT, MessageDeleter> msg) override {
void publish(std::unique_ptr<MessageT, MessageDeleter> msg) {
if (node_lifecycle_interface_ != nullptr &&
!node_lifecycle_interface_->is_activated()) {
// ignore publish request when publisher is not activated
Expand All @@ -88,7 +88,7 @@ class ClusterNodePublisher : public rclcpp::Publisher<MessageT, Alloc> {
*
* \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
Expand Down
6 changes: 3 additions & 3 deletions foros/src/cluster_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,9 +119,9 @@ rclcpp::CallbackGroup::SharedPtr ClusterNode::create_callback_group(
group_type, automatically_add_to_executor_with_node);
}

const std::vector<rclcpp::CallbackGroup::WeakPtr>
huchijwk marked this conversation as resolved.
Show resolved Hide resolved
&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(
Expand Down
2 changes: 1 addition & 1 deletion foros/test/test_raft.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down