Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
inflation_layer.cpp
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  * David V. Lu!!
37  *********************************************************************/
38 #include "nav2_costmap_2d/inflation_layer.hpp"
39 
40 #include <limits>
41 #include <map>
42 #include <vector>
43 #include <algorithm>
44 #include <utility>
45 
46 #include "nav2_costmap_2d/costmap_math.hpp"
47 #include "nav2_costmap_2d/footprint.hpp"
48 #include "pluginlib/class_list_macros.hpp"
49 #include "rclcpp/parameter_events_filter.hpp"
50 
52 
53 using nav2_costmap_2d::LETHAL_OBSTACLE;
54 using nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE;
55 using nav2_costmap_2d::NO_INFORMATION;
56 using rcl_interfaces::msg::ParameterType;
57 
58 namespace nav2_costmap_2d
59 {
60 
62 : inflation_radius_(0),
63  inscribed_radius_(0),
64  cost_scaling_factor_(0),
65  inflate_unknown_(false),
66  inflate_around_unknown_(false),
67  cell_inflation_radius_(0),
68  cached_cell_inflation_radius_(0),
69  resolution_(0),
70  cache_length_(0),
71  last_min_x_(std::numeric_limits<double>::lowest()),
72  last_min_y_(std::numeric_limits<double>::lowest()),
73  last_max_x_(std::numeric_limits<double>::max()),
74  last_max_y_(std::numeric_limits<double>::max())
75 {
76  access_ = new mutex_t();
77 }
78 
80 {
81  auto node = node_.lock();
82  if (dyn_params_handler_ && node) {
83  node->remove_on_set_parameters_callback(dyn_params_handler_.get());
84  }
85  dyn_params_handler_.reset();
86  delete access_;
87 }
88 
89 void
91 {
92  declareParameter("enabled", rclcpp::ParameterValue(true));
93  declareParameter("inflation_radius", rclcpp::ParameterValue(0.55));
94  declareParameter("cost_scaling_factor", rclcpp::ParameterValue(10.0));
95  declareParameter("inflate_unknown", rclcpp::ParameterValue(false));
96  declareParameter("inflate_around_unknown", rclcpp::ParameterValue(false));
97 
98  {
99  auto node = node_.lock();
100  if (!node) {
101  throw std::runtime_error{"Failed to lock node"};
102  }
103  node->get_parameter(name_ + "." + "enabled", enabled_);
104  node->get_parameter(name_ + "." + "inflation_radius", inflation_radius_);
105  node->get_parameter(name_ + "." + "cost_scaling_factor", cost_scaling_factor_);
106  node->get_parameter(name_ + "." + "inflate_unknown", inflate_unknown_);
107  node->get_parameter(name_ + "." + "inflate_around_unknown", inflate_around_unknown_);
108 
109  dyn_params_handler_ = node->add_on_set_parameters_callback(
110  std::bind(
112  this, std::placeholders::_1));
113  }
114 
115  current_ = true;
116  seen_.clear();
117  cached_distances_.clear();
118  cached_costs_.clear();
119  need_reinflation_ = false;
120  cell_inflation_radius_ = cellDistance(inflation_radius_);
121  matchSize();
122 }
123 
124 void
126 {
127  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
128  nav2_costmap_2d::Costmap2D * costmap = layered_costmap_->getCostmap();
129  resolution_ = costmap->getResolution();
130  cell_inflation_radius_ = cellDistance(inflation_radius_);
131  computeCaches();
132  seen_ = std::vector<bool>(costmap->getSizeInCellsX() * costmap->getSizeInCellsY(), false);
133 }
134 
135 void
137  double /*robot_x*/, double /*robot_y*/, double /*robot_yaw*/, double * min_x,
138  double * min_y, double * max_x, double * max_y)
139 {
140  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
141  if (need_reinflation_) {
142  last_min_x_ = *min_x;
143  last_min_y_ = *min_y;
144  last_max_x_ = *max_x;
145  last_max_y_ = *max_y;
146 
147  *min_x = std::numeric_limits<double>::lowest();
148  *min_y = std::numeric_limits<double>::lowest();
149  *max_x = std::numeric_limits<double>::max();
150  *max_y = std::numeric_limits<double>::max();
151  need_reinflation_ = false;
152  } else {
153  double tmp_min_x = last_min_x_;
154  double tmp_min_y = last_min_y_;
155  double tmp_max_x = last_max_x_;
156  double tmp_max_y = last_max_y_;
157  last_min_x_ = *min_x;
158  last_min_y_ = *min_y;
159  last_max_x_ = *max_x;
160  last_max_y_ = *max_y;
161  *min_x = std::min(tmp_min_x, *min_x) - inflation_radius_;
162  *min_y = std::min(tmp_min_y, *min_y) - inflation_radius_;
163  *max_x = std::max(tmp_max_x, *max_x) + inflation_radius_;
164  *max_y = std::max(tmp_max_y, *max_y) + inflation_radius_;
165  }
166 }
167 
168 void
170 {
171  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
172  inscribed_radius_ = layered_costmap_->getInscribedRadius();
173  cell_inflation_radius_ = cellDistance(inflation_radius_);
174  computeCaches();
175  need_reinflation_ = true;
176 
177  if (inflation_radius_ < inscribed_radius_) {
178  RCLCPP_ERROR(
179  logger_,
180  "The configured inflation radius (%.3f) is smaller than "
181  "the computed inscribed radius (%.3f) of your footprint, "
182  "it is highly recommended to set inflation radius to be at "
183  "least as big as the inscribed radius to avoid collisions",
184  inflation_radius_, inscribed_radius_);
185  }
186 
187  RCLCPP_DEBUG(
188  logger_, "InflationLayer::onFootprintChanged(): num footprint points: %zu,"
189  " inscribed_radius_ = %.3f, inflation_radius_ = %.3f",
190  layered_costmap_->getFootprint().size(), inscribed_radius_, inflation_radius_);
191 }
192 
193 void
195  nav2_costmap_2d::Costmap2D & master_grid, int min_i, int min_j,
196  int max_i,
197  int max_j)
198 {
199  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
200  if (!enabled_ || (cell_inflation_radius_ == 0)) {
201  return;
202  }
203 
204  // make sure the inflation list is empty at the beginning of the cycle (should always be true)
205  for (auto & dist : inflation_cells_) {
206  RCLCPP_FATAL_EXPRESSION(
207  logger_,
208  !dist.empty(), "The inflation list must be empty at the beginning of inflation");
209  }
210 
211  unsigned char * master_array = master_grid.getCharMap();
212  unsigned int size_x = master_grid.getSizeInCellsX(), size_y = master_grid.getSizeInCellsY();
213 
214  if (seen_.size() != size_x * size_y) {
215  RCLCPP_WARN(
216  logger_, "InflationLayer::updateCosts(): seen_ vector size is wrong");
217  seen_ = std::vector<bool>(size_x * size_y, false);
218  }
219 
220  std::fill(begin(seen_), end(seen_), false);
221 
222  // We need to include in the inflation cells outside the bounding
223  // box min_i...max_j, by the amount cell_inflation_radius_. Cells
224  // up to that distance outside the box can still influence the costs
225  // stored in cells inside the box.
226  const int base_min_i = min_i;
227  const int base_min_j = min_j;
228  const int base_max_i = max_i;
229  const int base_max_j = max_j;
230  min_i -= static_cast<int>(cell_inflation_radius_);
231  min_j -= static_cast<int>(cell_inflation_radius_);
232  max_i += static_cast<int>(cell_inflation_radius_);
233  max_j += static_cast<int>(cell_inflation_radius_);
234 
235  min_i = std::max(0, min_i);
236  min_j = std::max(0, min_j);
237  max_i = std::min(static_cast<int>(size_x), max_i);
238  max_j = std::min(static_cast<int>(size_y), max_j);
239 
240  // Inflation list; we append cells to visit in a list associated with
241  // its distance to the nearest obstacle
242  // We use a map<distance, list> to emulate the priority queue used before,
243  // with a notable performance boost
244 
245  // Start with lethal obstacles: by definition distance is 0.0
246  auto & obs_bin = inflation_cells_[0];
247  obs_bin.reserve(200);
248  for (int j = min_j; j < max_j; j++) {
249  for (int i = min_i; i < max_i; i++) {
250  int index = static_cast<int>(master_grid.getIndex(i, j));
251  unsigned char cost = master_array[index];
252  if (cost == LETHAL_OBSTACLE || (inflate_around_unknown_ && cost == NO_INFORMATION)) {
253  obs_bin.emplace_back(i, j, i, j);
254  }
255  }
256  }
257 
258  // Process cells by increasing distance; new cells are appended to the
259  // corresponding distance bin, so they
260  // can overtake previously inserted but farther away cells
261  for (auto & dist_bin : inflation_cells_) {
262  dist_bin.reserve(200);
263  for (std::size_t i = 0; i < dist_bin.size(); ++i) {
264  // Do not use iterator or for-range based loops to
265  // iterate though dist_bin, since it's size might
266  // change when a new cell is enqueued, invalidating all iterators
267  const CellData & cell = dist_bin[i];
268  unsigned int mx = cell.x_;
269  unsigned int my = cell.y_;
270  unsigned int sx = cell.src_x_;
271  unsigned int sy = cell.src_y_;
272  unsigned int index = master_grid.getIndex(mx, my);
273 
274  // ignore if already visited
275  if (seen_[index]) {
276  continue;
277  }
278 
279  seen_[index] = true;
280 
281  // assign the cost associated with the distance from an obstacle to the cell
282  unsigned char cost = costLookup(mx, my, sx, sy);
283  unsigned char old_cost = master_array[index];
284  // In order to avoid artifacts appeared out of boundary areas
285  // when some layer is going after inflation_layer,
286  // we need to apply inflation_layer only to inside of given bounds
287  if (static_cast<int>(mx) >= base_min_i &&
288  static_cast<int>(my) >= base_min_j &&
289  static_cast<int>(mx) < base_max_i &&
290  static_cast<int>(my) < base_max_j)
291  {
292  if (old_cost == NO_INFORMATION &&
293  (inflate_unknown_ ? (cost > FREE_SPACE) : (cost >= INSCRIBED_INFLATED_OBSTACLE)))
294  {
295  master_array[index] = cost;
296  } else {
297  master_array[index] = std::max(old_cost, cost);
298  }
299  }
300 
301  // attempt to put the neighbors of the current cell onto the inflation list
302  if (mx > 0) {
303  enqueue(index - 1, mx - 1, my, sx, sy);
304  }
305  if (my > 0) {
306  enqueue(index - size_x, mx, my - 1, sx, sy);
307  }
308  if (mx < size_x - 1) {
309  enqueue(index + 1, mx + 1, my, sx, sy);
310  }
311  if (my < size_y - 1) {
312  enqueue(index + size_x, mx, my + 1, sx, sy);
313  }
314  }
315  // This level of inflation_cells_ is not needed anymore. We can free the memory
316  // Note that dist_bin.clear() is not enough, because it won't free the memory
317  dist_bin = std::vector<CellData>();
318  }
319 
320  current_ = true;
321 }
322 
332 void
334  unsigned int index, unsigned int mx, unsigned int my,
335  unsigned int src_x, unsigned int src_y)
336 {
337  if (!seen_[index]) {
338  // we compute our distance table one cell further than the
339  // inflation radius dictates so we can make the check below
340  double distance = distanceLookup(mx, my, src_x, src_y);
341 
342  // we only want to put the cell in the list if it is within
343  // the inflation radius of the obstacle point
344  if (distance > cell_inflation_radius_) {
345  return;
346  }
347 
348  const unsigned int r = cell_inflation_radius_ + 2;
349 
350  // push the cell data onto the inflation list and mark
351  const auto dist = distance_matrix_[mx - src_x + r][my - src_y + r];
352  inflation_cells_[dist].emplace_back(mx, my, src_x, src_y);
353  }
354 }
355 
356 void
358 {
359  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
360  if (cell_inflation_radius_ == 0) {
361  return;
362  }
363 
364  cache_length_ = cell_inflation_radius_ + 2;
365 
366  // based on the inflation radius... compute distance and cost caches
367  if (cell_inflation_radius_ != cached_cell_inflation_radius_) {
368  cached_costs_.resize(cache_length_ * cache_length_);
369  cached_distances_.resize(cache_length_ * cache_length_);
370 
371  for (unsigned int i = 0; i < cache_length_; ++i) {
372  for (unsigned int j = 0; j < cache_length_; ++j) {
373  cached_distances_[i * cache_length_ + j] = hypot(i, j);
374  }
375  }
376 
377  cached_cell_inflation_radius_ = cell_inflation_radius_;
378  }
379 
380  for (unsigned int i = 0; i < cache_length_; ++i) {
381  for (unsigned int j = 0; j < cache_length_; ++j) {
382  cached_costs_[i * cache_length_ + j] = computeCost(cached_distances_[i * cache_length_ + j]);
383  }
384  }
385 
386  int max_dist = generateIntegerDistances();
387  inflation_cells_.clear();
388  inflation_cells_.resize(max_dist + 1);
389 }
390 
391 int
393 {
394  const int r = cell_inflation_radius_ + 2;
395  const int size = r * 2 + 1;
396 
397  std::vector<std::pair<int, int>> points;
398 
399  for (int y = -r; y <= r; y++) {
400  for (int x = -r; x <= r; x++) {
401  if (x * x + y * y <= r * r) {
402  points.emplace_back(x, y);
403  }
404  }
405  }
406 
407  std::sort(
408  points.begin(), points.end(),
409  [](const std::pair<int, int> & a, const std::pair<int, int> & b) -> bool {
410  return a.first * a.first + a.second * a.second < b.first * b.first + b.second * b.second;
411  }
412  );
413 
414  std::vector<std::vector<int>> distance_matrix(size, std::vector<int>(size, 0));
415  std::pair<int, int> last = {0, 0};
416  int level = 0;
417  for (auto const & p : points) {
418  if (p.first * p.first + p.second * p.second !=
419  last.first * last.first + last.second * last.second)
420  {
421  level++;
422  }
423  distance_matrix[p.first + r][p.second + r] = level;
424  last = p;
425  }
426 
427  distance_matrix_ = distance_matrix;
428  return level;
429 }
430 
435 rcl_interfaces::msg::SetParametersResult
437  std::vector<rclcpp::Parameter> parameters)
438 {
439  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
440  rcl_interfaces::msg::SetParametersResult result;
441 
442  bool need_cache_recompute = false;
443 
444  for (auto parameter : parameters) {
445  const auto & param_type = parameter.get_type();
446  const auto & param_name = parameter.get_name();
447  if (param_name.find(name_ + ".") != 0) {
448  continue;
449  }
450 
451  if (param_type == ParameterType::PARAMETER_DOUBLE) {
452  if (param_name == name_ + "." + "inflation_radius" &&
453  inflation_radius_ != parameter.as_double())
454  {
455  inflation_radius_ = parameter.as_double();
456  need_reinflation_ = true;
457  need_cache_recompute = true;
458  } else if (param_name == name_ + "." + "cost_scaling_factor" && // NOLINT
459  getCostScalingFactor() != parameter.as_double())
460  {
461  cost_scaling_factor_ = parameter.as_double();
462  need_reinflation_ = true;
463  need_cache_recompute = true;
464  }
465  } else if (param_type == ParameterType::PARAMETER_BOOL) {
466  if (param_name == name_ + "." + "enabled" && enabled_ != parameter.as_bool()) {
467  enabled_ = parameter.as_bool();
468  need_reinflation_ = true;
469  current_ = false;
470  } else if (param_name == name_ + "." + "inflate_unknown" && // NOLINT
471  inflate_unknown_ != parameter.as_bool())
472  {
473  inflate_unknown_ = parameter.as_bool();
474  need_reinflation_ = true;
475  } else if (param_name == name_ + "." + "inflate_around_unknown" && // NOLINT
476  inflate_around_unknown_ != parameter.as_bool())
477  {
478  inflate_around_unknown_ = parameter.as_bool();
479  need_reinflation_ = true;
480  }
481  }
482  }
483 
484  if (need_cache_recompute) {
485  matchSize();
486  }
487 
488  result.successful = true;
489  return result;
490 }
491 
492 } // namespace nav2_costmap_2d
Storage for cell information used during obstacle inflation.
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
Definition: costmap_2d.hpp:231
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
Definition: costmap_2d.cpp:259
double getResolution() const
Accessor for the resolution of the costmap.
Definition: costmap_2d.cpp:576
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:546
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:551
Layer to convolve costmap by robot's radius or footprint to prevent collisions and largely simply col...
void computeCaches()
Compute cached dsitances.
void updateCosts(nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j) override
Update the costs in the master costmap in the window.
unsigned int cellDistance(double world_dist)
Compute cached dsitances.
unsigned char costLookup(unsigned int mx, unsigned int my, unsigned int src_x, unsigned int src_y)
Lookup pre-computed costs.
void onInitialize() override
Initialization process of layer on startup.
void matchSize() override
Match the size of the master costmap.
void onFootprintChanged() override
Process updates on footprint changes to the inflation layer.
unsigned char computeCost(double distance) const
Given a distance, compute a cost.
int generateIntegerDistances()
Compute cached dsitances.
mutex_t * getMutex()
Get the mutex of the inflation information.
void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y) override
Update the bounds of the master costmap by this layer's update dimensions.
void enqueue(unsigned int index, unsigned int mx, unsigned int my, unsigned int src_x, unsigned int src_y)
Enqueue new cells in cache distance update search.
double distanceLookup(unsigned int mx, unsigned int my, unsigned int src_x, unsigned int src_y)
Lookup pre-computed distances.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
Abstract class for layered costmap plugin implementations.
Definition: layer.hpp:59
void declareParameter(const std::string &param_name, const rclcpp::ParameterValue &value)
Convenience functions for declaring ROS parameters.
Definition: layer.cpp:76
Costmap2D * getCostmap()
Get the costmap pointer to the master costmap.
double getInscribedRadius()
The radius of a circle centered at the origin of the robot which is just within all points and edges ...
const std::vector< geometry_msgs::msg::Point > & getFootprint()
Returns the latest footprint stored with setFootprint().