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