Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
savitzky_golay_smoother.hpp
1 // Copyright (c) 2022, Samsung Research America
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License. Reserved.
14 
15 #ifndef NAV2_SMOOTHER__SAVITZKY_GOLAY_SMOOTHER_HPP_
16 #define NAV2_SMOOTHER__SAVITZKY_GOLAY_SMOOTHER_HPP_
17 
18 #include <Eigen/Dense>
19 #include <cmath>
20 #include <vector>
21 #include <string>
22 #include <iostream>
23 #include <memory>
24 #include <queue>
25 #include <utility>
26 
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"
36 
37 namespace nav2_smoother
38 {
39 
45 {
46 public:
50  SavitzkyGolaySmoother() = default;
51 
55  ~SavitzkyGolaySmoother() override = default;
56 
57  void configure(
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;
62 
66  void cleanup() override {}
67 
71  void activate() override {}
72 
76  void deactivate() override {}
77 
85  bool smooth(
86  nav_msgs::msg::Path & path,
87  const rclcpp::Duration & max_time) override;
88 
92  void calculateCoefficients();
93 
94 protected:
103  bool smoothImpl(
104  nav_msgs::msg::Path & path,
105  bool & reversing_segment);
106 
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")};
111 };
112 
113 } // namespace nav2_smoother
114 
115 #endif // NAV2_SMOOTHER__SAVITZKY_GOLAY_SMOOTHER_HPP_
smoother interface that acts as a virtual base class for all smoother plugins
Definition: smoother.hpp:38
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.