Nav2 Navigation Stack - humble  humble
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 <cmath>
19 #include <vector>
20 #include <string>
21 #include <iostream>
22 #include <memory>
23 #include <queue>
24 #include <utility>
25 
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"
35 
36 namespace nav2_smoother
37 {
38 
44 {
45 public:
49  SavitzkyGolaySmoother() = default;
50 
54  ~SavitzkyGolaySmoother() override = default;
55 
56  void configure(
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;
61 
65  void cleanup() override {}
66 
70  void activate() override {}
71 
75  void deactivate() override {}
76 
84  bool smooth(
85  nav_msgs::msg::Path & path,
86  const rclcpp::Duration & max_time) override;
87 
88 protected:
97  bool smoothImpl(
98  nav_msgs::msg::Path & path,
99  bool & reversing_segment);
100 
101  bool do_refinement_;
102  int refinement_num_;
103  rclcpp::Logger logger_{rclcpp::get_logger("SGSmoother")};
104 };
105 
106 } // namespace nav2_smoother
107 
108 #endif // NAV2_SMOOTHER__SAVITZKY_GOLAY_SMOOTHER_HPP_
smoother interface that acts as a virtual base class for all smoother plugins
Definition: smoother.hpp:39
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.