Skip to content

Commit

Permalink
Also have to update the Simple Navigator
Browse files Browse the repository at this point in the history
  • Loading branch information
Michael Jeronimo committed May 8, 2019
1 parent 3012e89 commit 13b9379
Showing 1 changed file with 10 additions and 2 deletions.
12 changes: 10 additions & 2 deletions nav2_simple_navigator/src/simple_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -127,8 +127,12 @@ SimpleNavigator::navigateToPose(const std::shared_ptr<GoalHandle> goal_handle)

planner_client_->wait_for_action_server();

// Enable result awareness by providing an empty lambda function
auto planner_goal_options = typename rclcpp_action::Client<nav2_msgs::action::ComputePathToPose>::SendGoalOptions();
planner_goal_options.result_callback = [](auto){};

// Send the goal pose to the planner
auto planner_future_goal_handle = planner_client_->async_send_goal(planner_goal);
auto planner_future_goal_handle = planner_client_->async_send_goal(planner_goal, planner_goal_options);
if (rclcpp::spin_until_future_complete(client_node_, planner_future_goal_handle) !=
rclcpp::executor::FutureReturnCode::SUCCESS)
{
Expand Down Expand Up @@ -180,9 +184,13 @@ SimpleNavigator::navigateToPose(const std::shared_ptr<GoalHandle> goal_handle)
nav2_msgs::action::FollowPath::Goal controller_goal;
controller_goal.path = planner_result.result->path;

// Enable result awareness by providing an empty lambda function
auto controller_goal_options = typename rclcpp_action::Client<nav2_msgs::action::FollowPath>::SendGoalOptions();
controller_goal_options.result_callback = [](auto){};

// Send the goal pose to the local planner
RCLCPP_INFO(get_logger(), "Sending path to the controller to execute");
auto controller_future_goal_handle = controller_client_->async_send_goal(controller_goal);
auto controller_future_goal_handle = controller_client_->async_send_goal(controller_goal, controller_goal_options);
if (rclcpp::spin_until_future_complete(client_node_, controller_future_goal_handle) !=
rclcpp::executor::FutureReturnCode::SUCCESS)
{
Expand Down

0 comments on commit 13b9379

Please sign in to comment.