15 #ifndef NAV2_SMOOTHER__SAVITZKY_GOLAY_SMOOTHER_HPP_
16 #define NAV2_SMOOTHER__SAVITZKY_GOLAY_SMOOTHER_HPP_
18 #include <Eigen/Dense>
27 #include "nav2_core/smoother.hpp"
28 #include "nav2_smoother/smoother_utils.hpp"
29 #include "nav2_costmap_2d/costmap_2d.hpp"
30 #include "nav2_costmap_2d/cost_values.hpp"
31 #include "nav2_util/geometry_utils.hpp"
32 #include "nav2_ros_common/node_utils.hpp"
33 #include "nav_msgs/msg/path.hpp"
34 #include "angles/angles.h"
35 #include "tf2/utils.hpp"
37 namespace nav2_smoother
58 const nav2::LifecycleNode::WeakPtr &,
59 std::string name, std::shared_ptr<tf2_ros::Buffer>,
60 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber>,
61 std::shared_ptr<nav2_costmap_2d::FootprintSubscriber>)
override;
86 nav_msgs::msg::Path & path,
87 const rclcpp::Duration & max_time)
override;
104 nav_msgs::msg::Path & path,
105 bool & reversing_segment);
107 bool do_refinement_, enforce_path_inversion_;
108 int refinement_num_, window_size_, half_window_size_, poly_order_;
109 Eigen::VectorXd sg_coeffs_;
110 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 calculateCoefficients()
Method to calculate SavitzkyGolay Coefficients.
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.