Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
smoother.hpp
1 // Copyright (c) 2021 RoboTech Vision
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 NAV2_CORE__SMOOTHER_HPP_
16 #define NAV2_CORE__SMOOTHER_HPP_
17 
18 #include <memory>
19 #include <string>
20 
21 #include "nav2_costmap_2d/costmap_subscriber.hpp"
22 #include "nav2_costmap_2d/footprint_subscriber.hpp"
23 #include "tf2_ros/buffer.hpp"
24 #include "tf2_ros/transform_listener.hpp"
25 #include "nav2_ros_common/lifecycle_node.hpp"
26 #include "pluginlib/class_loader.hpp"
27 #include "nav_msgs/msg/path.hpp"
28 
29 
30 namespace nav2_core
31 {
32 
37 class Smoother
38 {
39 public:
40  using Ptr = std::shared_ptr<nav2_core::Smoother>;
41 
45  virtual ~Smoother() {}
46 
47  virtual void configure(
48  const nav2::LifecycleNode::WeakPtr &,
49  std::string name, std::shared_ptr<tf2_ros::Buffer>,
50  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber>,
51  std::shared_ptr<nav2_costmap_2d::FootprintSubscriber>) = 0;
52 
56  virtual void cleanup() = 0;
57 
61  virtual void activate() = 0;
62 
66  virtual void deactivate() = 0;
67 
75  virtual bool smooth(
76  nav_msgs::msg::Path & path,
77  const rclcpp::Duration & max_time) = 0;
78 };
79 
80 } // namespace nav2_core
81 
82 #endif // NAV2_CORE__SMOOTHER_HPP_
smoother interface that acts as a virtual base class for all smoother plugins
Definition: smoother.hpp:38
virtual void deactivate()=0
Method to deactivate smoother and any threads involved in execution.
virtual void activate()=0
Method to activate smoother and any threads involved in execution.
virtual void cleanup()=0
Method to cleanup resources.
virtual ~Smoother()
Virtual destructor.
Definition: smoother.hpp:45
virtual bool smooth(nav_msgs::msg::Path &path, const rclcpp::Duration &max_time)=0
Method to smooth given path.