Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
controller_error_plugins.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__CONTROLLER__CONTROLLER_ERROR_PLUGINS_HPP_
16 #define ERROR_CODES__CONTROLLER__CONTROLLER_ERROR_PLUGINS_HPP_
17 
18 #include <memory>
19 #include <string>
20 
21 #include "nav2_core/controller.hpp"
22 #include "nav2_core/controller_exceptions.hpp"
23 
24 namespace nav2_system_tests
25 {
26 
28 {
29 public:
30  UnknownErrorController() = default;
31  ~UnknownErrorController() = default;
32 
33  void configure(
34  const rclcpp_lifecycle::LifecycleNode::WeakPtr &,
35  std::string, std::shared_ptr<tf2_ros::Buffer>,
36  std::shared_ptr<nav2_costmap_2d::Costmap2DROS>) override {}
37 
38  void cleanup() {}
39 
40  void activate() {}
41 
42  void deactivate() {}
43 
44  void setPlan(const nav_msgs::msg::Path &) {}
45 
46  virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(
47  const geometry_msgs::msg::PoseStamped &,
48  const geometry_msgs::msg::Twist &,
50  {
51  throw nav2_core::ControllerException("Unknown Error");
52  }
53 
54  void setSpeedLimit(const double &, const bool &) {}
55 };
56 
58 {
59  virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(
60  const geometry_msgs::msg::PoseStamped &,
61  const geometry_msgs::msg::Twist &,
63  {
64  throw nav2_core::ControllerTFError("TF error");
65  }
66 };
67 
69 {
70  virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(
71  const geometry_msgs::msg::PoseStamped &,
72  const geometry_msgs::msg::Twist &,
74  {
75  throw nav2_core::FailedToMakeProgress("Failed to make progress");
76  }
77 };
78 
80 {
81  virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(
82  const geometry_msgs::msg::PoseStamped &,
83  const geometry_msgs::msg::Twist &,
85  {
86  throw nav2_core::PatienceExceeded("Patience exceeded");
87  }
88 };
89 
91 {
92  virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(
93  const geometry_msgs::msg::PoseStamped &,
94  const geometry_msgs::msg::Twist &,
96  {
97  throw nav2_core::InvalidPath("Invalid path");
98  }
99 };
100 
102 {
103  virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(
104  const geometry_msgs::msg::PoseStamped &,
105  const geometry_msgs::msg::Twist &,
107  {
108  throw nav2_core::NoValidControl("No valid control");
109  }
110 };
111 
112 } // namespace nav2_system_tests
113 
114 #endif // ERROR_CODES__CONTROLLER__CONTROLLER_ERROR_PLUGINS_HPP_
controller interface that acts as a virtual base class for all controller plugins
Definition: controller.hpp:61
Function-object for checking whether a goal has been reached.
void deactivate()
Method to deactive planner and any threads involved in execution.
void setSpeedLimit(const double &, const bool &)
Limits the maximum linear speed of the robot.
void setPlan(const nav_msgs::msg::Path &)
local setPlan - Sets the global plan
void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &, std::string, std::shared_ptr< tf2_ros::Buffer >, std::shared_ptr< nav2_costmap_2d::Costmap2DROS >) override
void activate()
Method to active planner and any threads involved in execution.
void cleanup()
Method to cleanup resources.
virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(const geometry_msgs::msg::PoseStamped &, const geometry_msgs::msg::Twist &, nav2_core::GoalChecker *)
Controller computeVelocityCommands - calculates the best command given the current pose and velocity.