Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
planner_error_plugin.hpp
1 // Copyright (c) 2022 Joshua Wallace
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 #ifndef ERROR_CODES__PLANNER__PLANNER_ERROR_PLUGIN_HPP_
16 #define ERROR_CODES__PLANNER__PLANNER_ERROR_PLUGIN_HPP_
17 
18 #include <string>
19 #include <memory>
20 
21 #include "rclcpp/rclcpp.hpp"
22 #include "geometry_msgs/msg/point.hpp"
23 #include "geometry_msgs/msg/pose_stamped.hpp"
24 
25 #include "nav2_core/global_planner.hpp"
26 #include "nav_msgs/msg/path.hpp"
27 #include "nav2_util/robot_utils.hpp"
28 #include "nav2_ros_common/lifecycle_node.hpp"
29 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
30 #include "nav2_core/planner_exceptions.hpp"
31 
32 namespace nav2_system_tests
33 {
34 
36 {
37 public:
38  UnknownErrorPlanner() = default;
39  ~UnknownErrorPlanner() = default;
40 
41  void configure(
42  const nav2::LifecycleNode::WeakPtr &,
43  std::string, std::shared_ptr<tf2_ros::Buffer>,
44  std::shared_ptr<nav2_costmap_2d::Costmap2DROS>) override {}
45 
46  void cleanup() override {}
47 
48  void activate() override {}
49 
50  void deactivate() override {}
51 
52  nav_msgs::msg::Path createPlan(
53  const geometry_msgs::msg::PoseStamped &,
54  const geometry_msgs::msg::PoseStamped &,
55  std::function<bool()>) override
56  {
57  throw nav2_core::PlannerException("Unknown Error");
58  }
59 };
60 
62 {
63  nav_msgs::msg::Path createPlan(
64  const geometry_msgs::msg::PoseStamped &,
65  const geometry_msgs::msg::PoseStamped &,
66  std::function<bool()>) override
67  {
68  throw nav2_core::StartOccupied("Start Occupied");
69  }
70 };
71 
73 {
74  nav_msgs::msg::Path createPlan(
75  const geometry_msgs::msg::PoseStamped &,
76  const geometry_msgs::msg::PoseStamped &,
77  std::function<bool()>) override
78  {
79  throw nav2_core::GoalOccupied("Goal occupied");
80  }
81 };
82 
84 {
85  nav_msgs::msg::Path createPlan(
86  const geometry_msgs::msg::PoseStamped &,
87  const geometry_msgs::msg::PoseStamped &,
88  std::function<bool()>) override
89  {
90  throw nav2_core::StartOutsideMapBounds("Start OutsideMapBounds");
91  }
92 };
93 
95 {
96  nav_msgs::msg::Path createPlan(
97  const geometry_msgs::msg::PoseStamped &,
98  const geometry_msgs::msg::PoseStamped &,
99  std::function<bool()>) override
100  {
101  throw nav2_core::GoalOutsideMapBounds("Goal outside map bounds");
102  }
103 };
104 
106 {
107  nav_msgs::msg::Path createPlan(
108  const geometry_msgs::msg::PoseStamped &,
109  const geometry_msgs::msg::PoseStamped &,
110  std::function<bool()>) override
111  {
112  return nav_msgs::msg::Path();
113  }
114 };
115 
116 
118 {
119  nav_msgs::msg::Path createPlan(
120  const geometry_msgs::msg::PoseStamped &,
121  const geometry_msgs::msg::PoseStamped &,
122  std::function<bool()>) override
123  {
124  throw nav2_core::PlannerTimedOut("Planner Timed Out");
125  }
126 };
127 
129 {
130  nav_msgs::msg::Path createPlan(
131  const geometry_msgs::msg::PoseStamped &,
132  const geometry_msgs::msg::PoseStamped &,
133  std::function<bool()>) override
134  {
135  throw nav2_core::PlannerTFError("TF Error");
136  }
137 };
138 
140 {
141  nav_msgs::msg::Path createPlan(
142  const geometry_msgs::msg::PoseStamped &,
143  const geometry_msgs::msg::PoseStamped &,
144  std::function<bool()>) override
145  {
146  throw nav2_core::NoViapointsGiven("No Via points given");
147  }
148 };
149 
151 {
152  nav_msgs::msg::Path createPlan(
153  const geometry_msgs::msg::PoseStamped &,
154  const geometry_msgs::msg::PoseStamped &,
155  std::function<bool()> cancel_checker) override
156  {
157  auto start_time = std::chrono::steady_clock::now();
158  while (rclcpp::ok() &&
159  std::chrono::steady_clock::now() - start_time < std::chrono::seconds(5))
160  {
161  if (cancel_checker()) {
162  throw nav2_core::PlannerCancelled("Planner Cancelled");
163  }
164  rclcpp::sleep_for(std::chrono::milliseconds(100));
165  }
166  throw nav2_core::PlannerException("Cancel is not called in time.");
167  }
168 };
169 
170 } // namespace nav2_system_tests
171 
172 
173 #endif // ERROR_CODES__PLANNER__PLANNER_ERROR_PLUGIN_HPP_
Abstract interface for global planners to adhere to with pluginlib.
void cleanup() override
Method to cleanup resources used on shutdown.
void deactivate() override
Method to deactivate planner and any threads involved in execution.
nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &, const geometry_msgs::msg::PoseStamped &, std::function< bool()>) override
Method create the plan from a starting and ending goal.
void configure(const nav2::LifecycleNode::WeakPtr &, std::string, std::shared_ptr< tf2_ros::Buffer >, std::shared_ptr< nav2_costmap_2d::Costmap2DROS >) override
void activate() override
Method to active planner and any threads involved in execution.