|
Nav2 Navigation Stack - jazzy
jazzy
ROS 2 Navigation Stack
|
A path smoother implementation using Savitzky Golay filters. More...
#include <nav2_smoother/include/nav2_smoother/savitzky_golay_smoother.hpp>


Public Member 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 |
| void | cleanup () override |
| Method to cleanup resources. | |
| void | activate () override |
| Method to activate smoother and any threads involved in execution. | |
| void | deactivate () override |
| Method to deactivate smoother and any threads involved in execution. | |
| bool | smooth (nav_msgs::msg::Path &path, const rclcpp::Duration &max_time) override |
| Method to smooth given path. More... | |
Public Member Functions inherited from nav2_core::Smoother | |
| virtual | ~Smoother () |
| Virtual destructor. | |
Protected Member Functions | |
| bool | smoothImpl (nav_msgs::msg::Path &path, bool &reversing_segment) |
| Smoother method - does the smoothing on a segment. More... | |
Protected Attributes | |
| bool | do_refinement_ |
| int | refinement_num_ |
| rclcpp::Logger | logger_ {rclcpp::get_logger("SGSmoother")} |
Additional Inherited Members | |
Public Types inherited from nav2_core::Smoother | |
| using | Ptr = std::shared_ptr< nav2_core::Smoother > |
A path smoother implementation using Savitzky Golay filters.
Definition at line 43 of file savitzky_golay_smoother.hpp.
|
overridevirtual |
Method to smooth given path.
| path | In-out path to be smoothed |
| max_time | Maximum duration smoothing should take |
Implements nav2_core::Smoother.
Definition at line 45 of file savitzky_golay_smoother.cpp.
|
protected |
Smoother method - does the smoothing on a segment.
| 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 |
Definition at line 92 of file savitzky_golay_smoother.cpp.