Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
simple_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/simple_smoother.hpp"
18 #include "nav2_core/smoother_exceptions.hpp"
19 
20 namespace nav2_smoother
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 SimpleSmoother::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  costmap_sub_ = costmap_sub;
34 
35  auto node = parent.lock();
36  logger_ = node->get_logger();
37 
38  declare_parameter_if_not_declared(
39  node, name + ".tolerance", rclcpp::ParameterValue(1e-10));
40  declare_parameter_if_not_declared(
41  node, name + ".max_its", rclcpp::ParameterValue(1000));
42  declare_parameter_if_not_declared(
43  node, name + ".w_data", rclcpp::ParameterValue(0.2));
44  declare_parameter_if_not_declared(
45  node, name + ".w_smooth", rclcpp::ParameterValue(0.3));
46  declare_parameter_if_not_declared(
47  node, name + ".do_refinement", rclcpp::ParameterValue(true));
48  declare_parameter_if_not_declared(
49  node, name + ".refinement_num", rclcpp::ParameterValue(2));
50  declare_parameter_if_not_declared(
51  node, name + ".enforce_path_inversion", rclcpp::ParameterValue(true));
52 
53  node->get_parameter(name + ".tolerance", tolerance_);
54  node->get_parameter(name + ".max_its", max_its_);
55  node->get_parameter(name + ".w_data", data_w_);
56  node->get_parameter(name + ".w_smooth", smooth_w_);
57  node->get_parameter(name + ".do_refinement", do_refinement_);
58  node->get_parameter(name + ".refinement_num", refinement_num_);
59  node->get_parameter(name + ".enforce_path_inversion", enforce_path_inversion_);
60 }
61 
63  nav_msgs::msg::Path & path,
64  const rclcpp::Duration & max_time)
65 {
66  auto costmap = costmap_sub_->getCostmap();
67 
68  steady_clock::time_point start = steady_clock::now();
69  double time_remaining = max_time.seconds();
70 
71  bool reversing_segment;
72  nav_msgs::msg::Path curr_path_segment;
73  curr_path_segment.header = path.header;
74 
75  std::vector<PathSegment> path_segments{PathSegment{
76  0u, static_cast<unsigned int>(path.poses.size() - 1)}};
77  if (enforce_path_inversion_) {
78  path_segments = findDirectionalPathSegments(path);
79  }
80 
81  std::lock_guard<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
82 
83  for (unsigned int i = 0; i != path_segments.size(); i++) {
84  if (path_segments[i].end - path_segments[i].start > 9) {
85  // Populate path segment
86  curr_path_segment.poses.clear();
87  std::copy(
88  path.poses.begin() + path_segments[i].start,
89  path.poses.begin() + path_segments[i].end + 1,
90  std::back_inserter(curr_path_segment.poses));
91 
92  // Make sure we're still able to smooth with time remaining
93  steady_clock::time_point now = steady_clock::now();
94  time_remaining = max_time.seconds() - duration_cast<duration<double>>(now - start).count();
95  refinement_ctr_ = 0;
96 
97  // Attempt to smooth the segment
98  // May throw SmootherTimedOut
99  smoothImpl(curr_path_segment, reversing_segment, costmap.get(), time_remaining);
100 
101  // Assemble the path changes to the main path
102  std::copy(
103  curr_path_segment.poses.begin(),
104  curr_path_segment.poses.end(),
105  path.poses.begin() + path_segments[i].start);
106  }
107  }
108 
109  return true;
110 }
111 
113  nav_msgs::msg::Path & path,
114  bool & reversing_segment,
115  const nav2_costmap_2d::Costmap2D * costmap,
116  const double & max_time)
117 {
118  steady_clock::time_point a = steady_clock::now();
119  rclcpp::Duration max_dur = rclcpp::Duration::from_seconds(max_time);
120 
121  int its = 0;
122  double change = tolerance_;
123  const unsigned int & path_size = path.poses.size();
124  double x_i, y_i, y_m1, y_ip1, y_i_org;
125  unsigned int mx, my;
126 
127  nav_msgs::msg::Path new_path = path;
128  nav_msgs::msg::Path last_path = path;
129 
130  while (change >= tolerance_) {
131  its += 1;
132  change = 0.0;
133 
134  // Make sure the smoothing function will converge
135  if (its >= max_its_) {
136  RCLCPP_WARN(
137  logger_,
138  "Number of iterations has exceeded limit of %i.", max_its_);
139  path = last_path;
140  updateApproximatePathOrientations(path, reversing_segment);
141  return;
142  }
143 
144  // Make sure still have time left to process
145  steady_clock::time_point b = steady_clock::now();
146  rclcpp::Duration timespan(duration_cast<duration<double>>(b - a));
147  if (timespan > max_dur) {
148  RCLCPP_WARN(
149  logger_,
150  "Smoothing time exceeded allowed duration of %0.2f.", max_time);
151  path = last_path;
152  updateApproximatePathOrientations(path, reversing_segment);
153  throw nav2_core::SmootherTimedOut("Smoothing time exceed allowed duration");
154  }
155 
156  for (unsigned int i = 1; i != path_size - 1; i++) {
157  for (unsigned int j = 0; j != 2; j++) {
158  x_i = getFieldByDim(path.poses[i], j);
159  y_i = getFieldByDim(new_path.poses[i], j);
160  y_m1 = getFieldByDim(new_path.poses[i - 1], j);
161  y_ip1 = getFieldByDim(new_path.poses[i + 1], j);
162  y_i_org = y_i;
163 
164  // Smooth based on local 3 point neighborhood and original data locations
165  y_i += data_w_ * (x_i - y_i) + smooth_w_ * (y_ip1 + y_m1 - (2.0 * y_i));
166  setFieldByDim(new_path.poses[i], j, y_i);
167  change += abs(y_i - y_i_org);
168  }
169 
170  // validate update is admissible, only checks cost if a valid costmap pointer is provided
171  float cost = 0.0;
172  if (costmap) {
173  costmap->worldToMap(
174  getFieldByDim(new_path.poses[i], 0),
175  getFieldByDim(new_path.poses[i], 1),
176  mx, my);
177  cost = static_cast<float>(costmap->getCost(mx, my));
178  }
179 
180  if (cost > nav2_costmap_2d::MAX_NON_OBSTACLE && cost != nav2_costmap_2d::NO_INFORMATION) {
181  RCLCPP_DEBUG(
182  rclcpp::get_logger("SmacPlannerSmoother"),
183  "Smoothing process resulted in an infeasible collision. "
184  "Returning the last path before the infeasibility was introduced.");
185  path = last_path;
186  updateApproximatePathOrientations(path, reversing_segment);
187  return;
188  }
189  }
190 
191  last_path = new_path;
192  }
193 
194  // Let's do additional refinement, it shouldn't take more than a couple milliseconds
195  // but really puts the path quality over the top.
196  if (do_refinement_ && refinement_ctr_ < refinement_num_) {
197  refinement_ctr_++;
198  smoothImpl(new_path, reversing_segment, costmap, max_time);
199  }
200 
201  updateApproximatePathOrientations(new_path, reversing_segment);
202  path = new_path;
203 }
204 
206  const geometry_msgs::msg::PoseStamped & msg, const unsigned int & dim)
207 {
208  if (dim == 0) {
209  return msg.pose.position.x;
210  } else if (dim == 1) {
211  return msg.pose.position.y;
212  } else {
213  return msg.pose.position.z;
214  }
215 }
216 
218  geometry_msgs::msg::PoseStamped & msg, const unsigned int dim,
219  const double & value)
220 {
221  if (dim == 0) {
222  msg.pose.position.x = value;
223  } else if (dim == 1) {
224  msg.pose.position.y = value;
225  } else {
226  msg.pose.position.z = value;
227  }
228 }
229 
230 } // namespace nav2_smoother
231 
232 #include "pluginlib/class_list_macros.hpp"
233 PLUGINLIB_EXPORT_CLASS(nav2_smoother::SimpleSmoother, nav2_core::Smoother)
smoother interface that acts as a virtual base class for all smoother plugins
Definition: smoother.hpp:39
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
Definition: costmap_2d.cpp:264
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:291
A path smoother implementation.
void setFieldByDim(geometry_msgs::msg::PoseStamped &msg, const unsigned int dim, const double &value)
Set the field value for a given dimension.
bool smooth(nav_msgs::msg::Path &path, const rclcpp::Duration &max_time) override
Method to smooth given path.
void smoothImpl(nav_msgs::msg::Path &path, bool &reversing_segment, const nav2_costmap_2d::Costmap2D *costmap, const double &max_time)
Smoother method - does the smoothing on a segment.
double getFieldByDim(const geometry_msgs::msg::PoseStamped &msg, const unsigned int &dim)
Get the field value for a given dimension.