Class Smoother

Class Documentation

class Smoother

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

Public Types

using Ptr = std::shared_ptr<nav2_core::Smoother>

Public Functions

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

Parameters:
  • path – In-out path to be smoothed

  • max_time – Maximum duration smoothing should take

Returns:

If smoothing was completed (true) or interrupted by time limit (false)