Nav2 Navigation Stack - kilted  kilted
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 rclcpp_lifecycle::LifecycleNode::WeakPtr & parent)
24 : node_(parent)
25 {
26  auto node = node_.lock();
27  nav2_util::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_ = rclcpp_action::create_client<Nav2Pose>(
41  node->get_node_base_interface(),
42  node->get_node_graph_interface(),
43  node->get_node_logging_interface(),
44  node->get_node_waitables_interface(),
45  "navigate_to_pose", callback_group_);
46 }
47 
49 {
50  nav_to_pose_client_.reset();
51 }
52 
54  const geometry_msgs::msg::PoseStamped & pose,
55  rclcpp::Duration remaining_staging_duration,
56  std::function<bool()> isPreempted,
57  bool recursed)
58 {
59  auto node = node_.lock();
60 
61  Nav2Pose::Goal goal;
62  goal.pose = pose;
63  goal.behavior_tree = navigator_bt_xml_;
64  const auto start_time = node->now();
65 
66  // Wait for server to be active
67  nav_to_pose_client_->wait_for_action_server(1s);
68  auto future_goal_handle = nav_to_pose_client_->async_send_goal(goal);
69  if (executor_.spin_until_future_complete(
70  future_goal_handle, 2s) == rclcpp::FutureReturnCode::SUCCESS)
71  {
72  auto future_result = nav_to_pose_client_->async_get_result(future_goal_handle.get());
73 
74  while (rclcpp::ok()) {
75  if (isPreempted()) {
76  auto cancel_future = nav_to_pose_client_->async_cancel_goal(future_goal_handle.get());
77  executor_.spin_until_future_complete(cancel_future, 1s);
78  throw opennav_docking_core::FailedToStage("Navigation request to staging pose preempted.");
79  }
80 
81  if (node->now() - start_time > remaining_staging_duration) {
82  auto cancel_future = nav_to_pose_client_->async_cancel_goal(future_goal_handle.get());
83  executor_.spin_until_future_complete(cancel_future, 1s);
84  throw opennav_docking_core::FailedToStage("Navigation request to staging pose timed out.");
85  }
86 
87  if (executor_.spin_until_future_complete(
88  future_result, 10ms) == rclcpp::FutureReturnCode::SUCCESS)
89  {
90  auto result = future_result.get();
91  if (result.code == rclcpp_action::ResultCode::SUCCEEDED &&
92  result.result->error_code == 0)
93  {
94  return; // Success!
95  } else {
96  RCLCPP_WARN(node->get_logger(), "Navigation request to staging pose failed.");
97  break;
98  }
99  }
100  }
101  }
102 
103  // Attempt to retry once using single iteration recursion
104  if (!recursed) {
105  auto elapsed_time = node->now() - start_time;
106  remaining_staging_duration = remaining_staging_duration - elapsed_time;
107  goToPose(pose, remaining_staging_duration, isPreempted, true);
108  return;
109  }
110 
111  throw opennav_docking_core::FailedToStage("Navigation request to staging pose failed.");
112 }
113 
114 } // namespace opennav_docking
Navigator(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent)
A constructor for opennav_docking::Navigator.
Definition: navigator.cpp:23
void activate()
An activation method.
Definition: navigator.cpp:32
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:53
void deactivate()
An deactivation method.
Definition: navigator.cpp:48
Failed to navigate to the staging pose.