Class SavitzkyGolaySmoother
- Defined in File savitzky_golay_smoother.hpp 
Inheritance Relationships
Base Type
- public nav2_core::Smoother
Class Documentation
- A path smoother implementation using Savitzky Golay filters. - Public Functions - A constructor for nav2_smoother::SavitzkyGolaySmoother. 
 - A destructor for nav2_smoother::SavitzkyGolaySmoother. 
 - Method to cleanup resources. 
 - Method to activate smoother and any threads involved in execution. 
 - Method to deactivate smoother and any threads involved in execution. 
 - 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 - 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