15 #ifndef NAV2_SMOOTHER__SAVITZKY_GOLAY_SMOOTHER_HPP_
16 #define NAV2_SMOOTHER__SAVITZKY_GOLAY_SMOOTHER_HPP_
26 #include "nav2_core/smoother.hpp"
27 #include "nav2_smoother/smoother_utils.hpp"
28 #include "nav2_costmap_2d/costmap_2d.hpp"
29 #include "nav2_costmap_2d/cost_values.hpp"
30 #include "nav2_util/geometry_utils.hpp"
31 #include "nav2_util/node_utils.hpp"
32 #include "nav_msgs/msg/path.hpp"
33 #include "angles/angles.h"
34 #include "tf2/utils.h"
36 namespace nav2_smoother
57 const rclcpp_lifecycle::LifecycleNode::WeakPtr &,
58 std::string name, std::shared_ptr<tf2_ros::Buffer>,
59 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber>,
60 std::shared_ptr<nav2_costmap_2d::FootprintSubscriber>)
override;
85 nav_msgs::msg::Path & path,
86 const rclcpp::Duration & max_time)
override;
98 nav_msgs::msg::Path & path,
99 bool & reversing_segment);
103 rclcpp::Logger logger_{rclcpp::get_logger(
"SGSmoother")};
smoother interface that acts as a virtual base class for all smoother plugins
A path smoother implementation using Savitzky Golay filters.
void deactivate() override
Method to deactivate smoother and any threads involved in execution.
void activate() override
Method to activate smoother and any threads involved in execution.
void cleanup() override
Method to cleanup resources.
bool smoothImpl(nav_msgs::msg::Path &path, bool &reversing_segment)
Smoother method - does the smoothing on a segment.
bool smooth(nav_msgs::msg::Path &path, const rclcpp::Duration &max_time) override
Method to smooth given path.
~SavitzkyGolaySmoother() override=default
A destructor for nav2_smoother::SavitzkyGolaySmoother.
SavitzkyGolaySmoother()=default
A constructor for nav2_smoother::SavitzkyGolaySmoother.