Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
savitzky_golay_smoother.cpp
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 #include <vector>
16 #include <memory>
17 #include "nav2_smoother/savitzky_golay_smoother.hpp"
18 
19 namespace nav2_smoother
20 {
21 
22 using namespace smoother_utils; // NOLINT
23 using namespace nav2_util::geometry_utils; // NOLINT
24 using namespace std::chrono; // NOLINT
25 using nav2_util::declare_parameter_if_not_declared;
26 
27 void SavitzkyGolaySmoother::configure(
28  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
29  std::string name, std::shared_ptr<tf2_ros::Buffer>/*tf*/,
30  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber>/*costmap_sub*/,
31  std::shared_ptr<nav2_costmap_2d::FootprintSubscriber>/*footprint_sub*/)
32 {
33  auto node = parent.lock();
34  logger_ = node->get_logger();
35 
36  declare_parameter_if_not_declared(
37  node, name + ".do_refinement", rclcpp::ParameterValue(true));
38  declare_parameter_if_not_declared(
39  node, name + ".refinement_num", rclcpp::ParameterValue(2));
40  node->get_parameter(name + ".do_refinement", do_refinement_);
41  node->get_parameter(name + ".refinement_num", refinement_num_);
42 }
43 
45  nav_msgs::msg::Path & path,
46  const rclcpp::Duration & max_time)
47 {
48  steady_clock::time_point start = steady_clock::now();
49  double time_remaining = max_time.seconds();
50 
51  bool success = true, reversing_segment;
52  nav_msgs::msg::Path curr_path_segment;
53  curr_path_segment.header = path.header;
54 
55  std::vector<PathSegment> path_segments = findDirectionalPathSegments(path);
56 
57  for (unsigned int i = 0; i != path_segments.size(); i++) {
58  if (path_segments[i].end - path_segments[i].start > 9) {
59  // Populate path segment
60  curr_path_segment.poses.clear();
61  std::copy(
62  path.poses.begin() + path_segments[i].start,
63  path.poses.begin() + path_segments[i].end + 1,
64  std::back_inserter(curr_path_segment.poses));
65 
66  // Make sure we're still able to smooth with time remaining
67  steady_clock::time_point now = steady_clock::now();
68  time_remaining = max_time.seconds() - duration_cast<duration<double>>(now - start).count();
69 
70  if (time_remaining <= 0.0) {
71  RCLCPP_WARN(
72  logger_,
73  "Smoothing time exceeded allowed duration of %0.2f.", max_time.seconds());
74  return false;
75  }
76 
77  // Smooth path segment
78  success = success && smoothImpl(curr_path_segment, reversing_segment);
79 
80  // Assemble the path changes to the main path
81  std::copy(
82  curr_path_segment.poses.begin(),
83  curr_path_segment.poses.end(),
84  path.poses.begin() + path_segments[i].start);
85  }
86  }
87 
88  return success;
89 }
90 
92  nav_msgs::msg::Path & path,
93  bool & reversing_segment)
94 {
95  // Must be at least 10 in length to enter function
96  const unsigned int & path_size = path.poses.size();
97 
98  // 7-point SG filter
99  const std::array<double, 7> filter = {
100  -2.0 / 21.0,
101  3.0 / 21.0,
102  6.0 / 21.0,
103  7.0 / 21.0,
104  6.0 / 21.0,
105  3.0 / 21.0,
106  -2.0 / 21.0};
107 
108  auto applyFilter = [&](const std::vector<geometry_msgs::msg::Point> & data)
109  -> geometry_msgs::msg::Point
110  {
111  geometry_msgs::msg::Point val;
112  for (unsigned int i = 0; i != filter.size(); i++) {
113  val.x += filter[i] * data[i].x;
114  val.y += filter[i] * data[i].y;
115  }
116  return val;
117  };
118 
119  auto applyFilterOverAxes =
120  [&](std::vector<geometry_msgs::msg::PoseStamped> & plan_pts) -> void
121  {
122  // Handle initial boundary conditions, first point is fixed
123  unsigned int idx = 1;
124  plan_pts[idx].pose.position = applyFilter(
125  {
126  plan_pts[idx - 1].pose.position,
127  plan_pts[idx - 1].pose.position,
128  plan_pts[idx - 1].pose.position,
129  plan_pts[idx].pose.position,
130  plan_pts[idx + 1].pose.position,
131  plan_pts[idx + 2].pose.position,
132  plan_pts[idx + 3].pose.position});
133 
134  idx++;
135  plan_pts[idx].pose.position = applyFilter(
136  {
137  plan_pts[idx - 2].pose.position,
138  plan_pts[idx - 2].pose.position,
139  plan_pts[idx - 1].pose.position,
140  plan_pts[idx].pose.position,
141  plan_pts[idx + 1].pose.position,
142  plan_pts[idx + 2].pose.position,
143  plan_pts[idx + 3].pose.position});
144 
145  // Apply nominal filter
146  for (idx = 3; idx < path_size - 4; ++idx) {
147  plan_pts[idx].pose.position = applyFilter(
148  {
149  plan_pts[idx - 3].pose.position,
150  plan_pts[idx - 2].pose.position,
151  plan_pts[idx - 1].pose.position,
152  plan_pts[idx].pose.position,
153  plan_pts[idx + 1].pose.position,
154  plan_pts[idx + 2].pose.position,
155  plan_pts[idx + 3].pose.position});
156  }
157 
158  // Handle terminal boundary conditions, last point is fixed
159  idx++;
160  plan_pts[idx].pose.position = applyFilter(
161  {
162  plan_pts[idx - 3].pose.position,
163  plan_pts[idx - 2].pose.position,
164  plan_pts[idx - 1].pose.position,
165  plan_pts[idx].pose.position,
166  plan_pts[idx + 1].pose.position,
167  plan_pts[idx + 2].pose.position,
168  plan_pts[idx + 2].pose.position});
169 
170  idx++;
171  plan_pts[idx].pose.position = applyFilter(
172  {
173  plan_pts[idx - 3].pose.position,
174  plan_pts[idx - 2].pose.position,
175  plan_pts[idx - 1].pose.position,
176  plan_pts[idx].pose.position,
177  plan_pts[idx + 1].pose.position,
178  plan_pts[idx + 1].pose.position,
179  plan_pts[idx + 1].pose.position});
180  };
181 
182  applyFilterOverAxes(path.poses);
183 
184  // Lets do additional refinement, it shouldn't take more than a couple milliseconds
185  if (do_refinement_) {
186  for (int i = 0; i < refinement_num_; i++) {
187  applyFilterOverAxes(path.poses);
188  }
189  }
190 
191  updateApproximatePathOrientations(path, reversing_segment);
192  return true;
193 }
194 
195 } // namespace nav2_smoother
196 
197 #include "pluginlib/class_list_macros.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.
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.