Class SavitzkyGolaySmoother

Inheritance Relationships

Base Type

  • public nav2_core::Smoother

Class Documentation

class SavitzkyGolaySmoother : public nav2_core::Smoother

A path smoother implementation using Savitzky Golay filters.

Public Functions

SavitzkyGolaySmoother() = default

A constructor for nav2_smoother::SavitzkyGolaySmoother.

~SavitzkyGolaySmoother() override = default

A destructor for nav2_smoother::SavitzkyGolaySmoother.

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>) override
inline virtual void cleanup() override

Method to cleanup resources.

inline virtual void activate() override

Method to activate smoother and any threads involved in execution.

inline virtual void deactivate() override

Method to deactivate smoother and any threads involved in execution.

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

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)

Protected Functions

bool smoothImpl(nav_msgs::msg::Path &path, bool &reversing_segment)

Smoother method - does the smoothing on a segment.

Parameters:
  • path – Reference to path

  • reversing_segment – Return if this is a reversing segment

  • costmap – Pointer to minimal costmap

  • max_time – Maximum time to compute, stop early if over limit

Returns:

If smoothing was successful

Protected Attributes

bool do_refinement_
int refinement_num_
rclcpp::Logger logger_ = {rclcpp::get_logger("SGSmoother")}