15 #ifndef NAV2_CORE__SMOOTHER_HPP_
16 #define NAV2_CORE__SMOOTHER_HPP_
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"
40 using Ptr = std::shared_ptr<nav2_core::Smoother>;
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;
76 nav_msgs::msg::Path & path,
77 const rclcpp::Duration & max_time) = 0;
smoother interface that acts as a virtual base class for all smoother plugins
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.
virtual bool smooth(nav_msgs::msg::Path &path, const rclcpp::Duration &max_time)=0
Method to smooth given path.