Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
Public Types | Public Member Functions | List of all members
nav2_core::Smoother Class Referenceabstract

smoother interface that acts as a virtual base class for all smoother plugins More...

#include <nav2_core/include/nav2_core/smoother.hpp>

Inheritance diagram for nav2_core::Smoother:
Inheritance graph
[legend]

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...
 

Detailed Description

smoother interface that acts as a virtual base class for all smoother plugins

Definition at line 38 of file smoother.hpp.

Member Function Documentation

◆ smooth()

virtual bool nav2_core::Smoother::smooth ( nav_msgs::msg::Path &  path,
const rclcpp::Duration &  max_time 
)
pure virtual

Method to smooth given path.

Parameters
pathIn-out path to be smoothed
max_timeMaximum duration smoothing should take
Returns
If smoothing was completed (true) or interrupted by time limit (false)

Implemented in nav2_smoother::SimpleSmoother, nav2_smoother::SavitzkyGolaySmoother, nav2_constrained_smoother::ConstrainedSmoother, and nav2_system_tests::UnknownErrorSmoother.


The documentation for this class was generated from the following file: