Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
smoother_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__SMOOTHER__SMOOTHER_ERROR_PLUGIN_HPP_
16 #define ERROR_CODES__SMOOTHER__SMOOTHER_ERROR_PLUGIN_HPP_
17 
18 #include <string>
19 #include <memory>
20 
21 #include "nav2_core/smoother.hpp"
22 #include "nav2_core/smoother_exceptions.hpp"
23 
24 namespace nav2_system_tests
25 {
26 
28 {
29 public:
30  void configure(
31  const nav2::LifecycleNode::WeakPtr &,
32  std::string, std::shared_ptr<tf2_ros::Buffer>,
33  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber>,
34  std::shared_ptr<nav2_costmap_2d::FootprintSubscriber>) override {}
35 
36  void cleanup() override {}
37 
38  void activate() override {}
39 
40  void deactivate() override {}
41 
42  bool smooth(
43  nav_msgs::msg::Path &,
44  const rclcpp::Duration &) override
45  {
46  throw nav2_core::SmootherException("Unknown Smoother exception");
47  }
48 };
49 
51 {
52  bool smooth(
53  nav_msgs::msg::Path &,
54  const rclcpp::Duration &)
55  {
56  throw nav2_core::SmootherTimedOut("Smoother timedOut");
57  }
58 };
59 
61 {
62  bool smooth(
63  nav_msgs::msg::Path &,
64  const rclcpp::Duration &)
65  {
66  throw nav2_core::SmoothedPathInCollision("Smoother path in collision");
67  }
68 };
69 
71 {
72  bool smooth(
73  nav_msgs::msg::Path &,
74  const rclcpp::Duration &)
75  {
76  throw nav2_core::FailedToSmoothPath("Failed to smooth path");
77  }
78 };
79 
81 {
82  bool smooth(
83  nav_msgs::msg::Path &,
84  const rclcpp::Duration &)
85  {
86  throw nav2_core::InvalidPath("Invalid path");
87  }
88 };
89 
90 } // namespace nav2_system_tests
91 
92 #endif // ERROR_CODES__SMOOTHER__SMOOTHER_ERROR_PLUGIN_HPP_
smoother interface that acts as a virtual base class for all smoother plugins
Definition: smoother.hpp:38
void cleanup() override
Method to cleanup resources.
void deactivate() override
Method to deactivate smoother and any threads involved in execution.
bool smooth(nav_msgs::msg::Path &, const rclcpp::Duration &) override
Method to smooth given path.
void activate() override
Method to activate smoother and any threads involved in execution.