Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
smoother interface that acts as a virtual base class for all smoother plugins More...
#include <nav2_core/include/nav2_core/smoother.hpp>
Public Types | |
using | Ptr = std::shared_ptr< nav2_core::Smoother > |
Public Member Functions | |
virtual | ~Smoother () |
Virtual destructor. | |
virtual void | configure (const rclcpp_lifecycle::LifecycleNode::WeakPtr &, std::string name, std::shared_ptr< tf2_ros::Buffer >, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber >, std::shared_ptr< nav2_costmap_2d::FootprintSubscriber >)=0 |
virtual void | cleanup ()=0 |
Method to cleanup resources. | |
virtual void | activate ()=0 |
Method to activate smoother and any threads involved in execution. | |
virtual void | deactivate ()=0 |
Method to deactivate smoother and any threads involved in execution. | |
virtual bool | smooth (nav_msgs::msg::Path &path, const rclcpp::Duration &max_time)=0 |
Method to smooth given path. More... | |
smoother interface that acts as a virtual base class for all smoother plugins
Definition at line 38 of file smoother.hpp.
|
pure virtual |
Method to smooth given path.
path | In-out path to be smoothed |
max_time | Maximum duration smoothing should take |
Implemented in nav2_smoother::SimpleSmoother, nav2_smoother::SavitzkyGolaySmoother, and nav2_constrained_smoother::ConstrainedSmoother.