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