Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
navigator.cpp
1 // Copyright (c) 2024 Open Navigation LLC
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <chrono>
16 #include "opennav_docking/navigator.hpp"
17 
18 namespace opennav_docking
19 {
20 
21 using namespace std::chrono_literals; // NOLINT
22 
23 Navigator::Navigator(const nav2::LifecycleNode::WeakPtr & parent)
24 : node_(parent)
25 {
26  auto node = node_.lock();
27  nav2::declare_parameter_if_not_declared(
28  node, "navigator_bt_xml", rclcpp::ParameterValue(std::string("")));
29  node->get_parameter("navigator_bt_xml", navigator_bt_xml_);
30 }
31 
33 {
34  // Need separate callback group and executor to call Nav action within docking action
35  auto node = node_.lock();
36  callback_group_ = node->create_callback_group(
37  rclcpp::CallbackGroupType::MutuallyExclusive,
38  false);
39  executor_.add_callback_group(callback_group_, node->get_node_base_interface());
40  nav_to_pose_client_ = node->create_action_client<Nav2Pose>(
41  "navigate_to_pose", callback_group_);
42 }
43 
45 {
46  nav_to_pose_client_.reset();
47 }
48 
50  const geometry_msgs::msg::PoseStamped & pose,
51  rclcpp::Duration remaining_staging_duration,
52  std::function<bool()> isPreempted,
53  bool recursed)
54 {
55  auto node = node_.lock();
56 
57  Nav2Pose::Goal goal;
58  goal.pose = pose;
59  goal.behavior_tree = navigator_bt_xml_;
60  const auto start_time = node->now();
61 
62  // Wait for server to be active
63  nav_to_pose_client_->wait_for_action_server(1s);
64  auto future_goal_handle = nav_to_pose_client_->async_send_goal(goal);
65  if (executor_.spin_until_future_complete(
66  future_goal_handle, 2s) == rclcpp::FutureReturnCode::SUCCESS)
67  {
68  auto future_result = nav_to_pose_client_->async_get_result(future_goal_handle.get());
69 
70  while (rclcpp::ok()) {
71  if (isPreempted()) {
72  auto cancel_future = nav_to_pose_client_->async_cancel_goal(future_goal_handle.get());
73  executor_.spin_until_future_complete(cancel_future, 1s);
74  throw opennav_docking_core::FailedToStage("Navigation request to staging pose preempted.");
75  }
76 
77  if (node->now() - start_time > remaining_staging_duration) {
78  auto cancel_future = nav_to_pose_client_->async_cancel_goal(future_goal_handle.get());
79  executor_.spin_until_future_complete(cancel_future, 1s);
80  throw opennav_docking_core::FailedToStage("Navigation request to staging pose timed out.");
81  }
82 
83  if (executor_.spin_until_future_complete(
84  future_result, 10ms) == rclcpp::FutureReturnCode::SUCCESS)
85  {
86  auto result = future_result.get();
87  if (result.code == rclcpp_action::ResultCode::SUCCEEDED &&
88  result.result->error_code == 0)
89  {
90  return; // Success!
91  } else {
92  RCLCPP_WARN(node->get_logger(), "Navigation request to staging pose failed.");
93  break;
94  }
95  }
96  }
97  }
98 
99  // Attempt to retry once using single iteration recursion
100  if (!recursed) {
101  auto elapsed_time = node->now() - start_time;
102  remaining_staging_duration = remaining_staging_duration - elapsed_time;
103  goToPose(pose, remaining_staging_duration, isPreempted, true);
104  return;
105  }
106 
107  throw opennav_docking_core::FailedToStage("Navigation request to staging pose failed.");
108 }
109 
110 } // namespace opennav_docking
void activate()
An activation method.
Definition: navigator.cpp:32
Navigator(const nav2::LifecycleNode::WeakPtr &parent)
A constructor for opennav_docking::Navigator.
Definition: navigator.cpp:23
void goToPose(const geometry_msgs::msg::PoseStamped &pose, rclcpp::Duration remaining_staging_duration, std::function< bool()> isPreempted, bool recursed=false)
An method to go to a particular pose May throw exception if fails to navigate or communicate Blocks u...
Definition: navigator.cpp:49
void deactivate()
An deactivation method.
Definition: navigator.cpp:44
Failed to navigate to the staging pose.