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

Reduce nodes for nav2_waypoint_follower #2441

Merged
merged 2 commits into from
Jul 12, 2021
Merged
Show file tree
Hide file tree
Changes from all 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
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,8 @@ class WaypointFollower : public nav2_util::LifecycleNode
// Our action server
std::unique_ptr<ActionServer> action_server_;
ActionClient::SharedPtr nav_to_pose_client_;
rclcpp::Node::SharedPtr client_node_;
rclcpp::CallbackGroup::SharedPtr callback_group_;
rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
std::shared_future<rclcpp_action::ClientGoalHandle<ClientT>::SharedPtr> future_goal_handle_;
bool stop_on_failure_;
ActionStatus current_goal_status_;
Expand Down
23 changes: 12 additions & 11 deletions nav2_waypoint_follower/src/waypoint_follower.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,16 +56,17 @@ WaypointFollower::on_configure(const rclcpp_lifecycle::State & /*state*/)
loop_rate_ = get_parameter("loop_rate").as_int();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It's worth a migration guide entry to talk about these changes https://github.com/ros-planning/navigation.ros.org/blob/master/migration/Galactic.rst. Please add a new subsection titled Reduce Nodes and Executors where you briefly (1-2 sentences) describe the aim of the work and then start a bulleted list of changes made with PR links. You should plan to update that section each PR you submit so that we can keep track in docs the updates and their relevance.

waypoint_task_executor_id_ = get_parameter("waypoint_task_executor_plugin").as_string();

std::vector<std::string> new_args = rclcpp::NodeOptions().arguments();
new_args.push_back("--ros-args");
new_args.push_back("-r");
new_args.push_back(std::string("__node:=") + this->get_name() + "_rclcpp_node");
new_args.push_back("--");
client_node_ = std::make_shared<rclcpp::Node>(
"_", "", rclcpp::NodeOptions().arguments(new_args));
callback_group_ = create_callback_group(
rclcpp::CallbackGroupType::MutuallyExclusive,
false);
callback_group_executor_.add_callback_group(callback_group_, get_node_base_interface());

nav_to_pose_client_ = rclcpp_action::create_client<ClientT>(
client_node_, "navigate_to_pose");
get_node_base_interface(),
get_node_graph_interface(),
get_node_logging_interface(),
get_node_waitables_interface(),
"navigate_to_pose", callback_group_);

action_server_ = std::make_unique<ActionServer>(
get_node_base_interface(),
Expand Down Expand Up @@ -167,9 +168,9 @@ WaypointFollower::followWaypoints()
// Check if asked to stop processing action
if (action_server_->is_cancel_requested()) {
auto cancel_future = nav_to_pose_client_->async_cancel_all_goals();
rclcpp::spin_until_future_complete(client_node_, cancel_future);
callback_group_executor_.spin_until_future_complete(cancel_future);
// for result callback processing
spin_some(client_node_);
callback_group_executor_.spin_some();
action_server_->terminate_all();
return;
}
Expand Down Expand Up @@ -267,7 +268,7 @@ WaypointFollower::followWaypoints()
"Processing waypoint %i...", goal_index);
}

rclcpp::spin_some(client_node_);
callback_group_executor_.spin_some();
r.sleep();
}
}
Expand Down