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