costmap_2d
inflation_layer.cpp
Go to the documentation of this file.
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 <algorithm>
41 #include <costmap_2d/footprint.h>
42 #include <boost/thread.hpp>
43 #include <pluginlib/class_list_macros.hpp>
44 
45 PLUGINLIB_EXPORT_CLASS(costmap_2d::InflationLayer, costmap_2d::Layer)
46 
50 
51 namespace costmap_2d
52 {
53 
55  : resolution_(0)
56  , inflation_radius_(0)
57  , dilation_radius_(0)
58  , target_cell_value_(0)
59  , dilation_cell_value_ (0)
60  , use_footprint_(true)
61  , inscribed_radius_(0)
62  , weight_(0)
63  , inflate_unknown_(false)
64  , cell_inflation_radius_(0)
65  , cached_cell_inflation_radius_(0)
66  , dsrv_(NULL)
67  , seen_(NULL)
68  , cached_costs_(NULL)
69  , cached_distances_(NULL)
70  , last_min_x_(-std::numeric_limits<float>::max())
71  , last_min_y_(-std::numeric_limits<float>::max())
72  , last_max_x_(std::numeric_limits<float>::max())
73  , last_max_y_(std::numeric_limits<float>::max())
74 {
75  inflation_access_ = new boost::recursive_mutex();
76 }
77 
79 {
80  {
81  boost::unique_lock < boost::recursive_mutex > lock(*inflation_access_);
82  ros::NodeHandle nh("~/" + name_), g_nh;
83  current_ = true;
84  if (seen_)
85  delete[] seen_;
86  seen_ = NULL;
87  seen_size_ = 0;
88  need_reinflation_ = false;
89 
90  dynamic_reconfigure::Server<costmap_2d::InflationPluginConfig>::CallbackType cb =
91  [this](auto& config, auto level){ reconfigureCB(config, level); };
92 
93  if (dsrv_ != NULL){
94  dsrv_->clearCallback();
95  dsrv_->setCallback(cb);
96  }
97  else
98  {
99  dsrv_ = new dynamic_reconfigure::Server<costmap_2d::InflationPluginConfig>(ros::NodeHandle("~/" + name_));
100  dsrv_->setCallback(cb);
101  }
102  }
103 
104  matchSize();
105 }
106 
107 void InflationLayer::reconfigureCB(costmap_2d::InflationPluginConfig &config, uint32_t level)
108 {
109  setInflationParameters(config.inflation_radius, config.cost_scaling_factor);
110 
111  use_footprint_ = config.use_footprint;
112  if (!use_footprint_)
113  dilation_radius_ = config.dilation_radius;
114 
115  target_cell_value_ = config.target_cell_value;
116  dilation_cell_value_ = config.dilation_cell_value;
117 
118  inflation_radius_ = config.inflation_radius;
120  need_reinflation_ = true;
121  computeCaches();
122 
123  if (enabled_ != config.enabled || inflate_unknown_ != config.inflate_unknown) {
124  enabled_ = config.enabled;
125  inflate_unknown_ = config.inflate_unknown;
126  need_reinflation_ = true;
127  }
128 }
129 
131 {
132  boost::unique_lock < boost::recursive_mutex > lock(*inflation_access_);
134  resolution_ = costmap->getResolution();
136  computeCaches();
137 
138  unsigned int size_x = costmap->getSizeInCellsX(), size_y = costmap->getSizeInCellsY();
139  if (seen_)
140  delete[] seen_;
141  seen_size_ = size_x * size_y;
142  seen_ = new bool[seen_size_];
143 }
144 
145 void InflationLayer::updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x,
146  double* min_y, double* max_x, double* max_y)
147 {
148  if (need_reinflation_)
149  {
150  last_min_x_ = *min_x;
151  last_min_y_ = *min_y;
152  last_max_x_ = *max_x;
153  last_max_y_ = *max_y;
154  // For some reason when I make these -<double>::max() it does not
155  // work with Costmap2D::worldToMapEnforceBounds(), so I'm using
156  // -<float>::max() instead.
161  need_reinflation_ = false;
162  }
163  else
164  {
165  double tmp_min_x = last_min_x_;
166  double tmp_min_y = last_min_y_;
167  double tmp_max_x = last_max_x_;
168  double tmp_max_y = last_max_y_;
169  last_min_x_ = *min_x;
170  last_min_y_ = *min_y;
171  last_max_x_ = *max_x;
172  last_max_y_ = *max_y;
173  *min_x = std::min(tmp_min_x, *min_x) - inflation_radius_;
174  *min_y = std::min(tmp_min_y, *min_y) - inflation_radius_;
175  *max_x = std::max(tmp_max_x, *max_x) + inflation_radius_;
176  *max_y = std::max(tmp_max_y, *max_y) + inflation_radius_;
177  }
178 }
179 
181 {
182  if (use_footprint_)
183  {
186  computeCaches();
187  need_reinflation_ = true;
188 
189  ROS_DEBUG("InflationLayer::onFootprintChanged(): num footprint points: %lu,"
190  " inscribed_radius_ = %.3f, inflation_radius_ = %.3f",
192  }
193 }
194 
195 void InflationLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j)
196 {
197  boost::unique_lock < boost::recursive_mutex > lock(*inflation_access_);
198  if (cell_inflation_radius_ == 0)
199  return;
200 
201  // make sure the inflation list is empty at the beginning of the cycle (should always be true)
202  ROS_ASSERT_MSG(inflation_cells_.empty(), "The inflation list must be empty at the beginning of inflation");
203 
204  unsigned char* master_array = master_grid.getCharMap();
205  unsigned int size_x = master_grid.getSizeInCellsX(), size_y = master_grid.getSizeInCellsY();
206 
207  if (seen_ == NULL) {
208  ROS_WARN("InflationLayer::updateCosts(): seen_ array is NULL");
209  seen_size_ = size_x * size_y;
210  seen_ = new bool[seen_size_];
211  }
212  else if (seen_size_ != size_x * size_y)
213  {
214  ROS_WARN("InflationLayer::updateCosts(): seen_ array size is wrong");
215  delete[] seen_;
216  seen_size_ = size_x * size_y;
217  seen_ = new bool[seen_size_];
218  }
219  memset(seen_, false, size_x * size_y * sizeof(bool));
220 
221  // We need to include in the inflation cells outside the bounding
222  // box min_i...max_j, by the amount cell_inflation_radius_. Cells
223  // up to that distance outside the box can still influence the costs
224  // stored in cells inside the box.
225  min_i -= cell_inflation_radius_;
226  min_j -= cell_inflation_radius_;
227  max_i += cell_inflation_radius_;
228  max_j += cell_inflation_radius_;
229 
230  min_i = std::max(0, min_i);
231  min_j = std::max(0, min_j);
232  max_i = std::min(int(size_x), max_i);
233  max_j = std::min(int(size_y), max_j);
234 
235  // Inflation list; we append cells to visit in a list associated with its distance to the nearest obstacle
236  // We use a map<distance, list> to emulate the priority queue used before, with a notable performance boost
237 
238  // Start with lethal obstacles: by definition distance is 0.0
239  std::vector<CellData>& obs_bin = inflation_cells_[0.0];
240  for (int j = min_j; j < max_j; j++)
241  {
242  for (int i = min_i; i < max_i; i++)
243  {
244  int index = master_grid.getIndex(i, j);
245  unsigned char cost = master_array[index];
246  if (cost == target_cell_value_)
247  {
248  obs_bin.push_back(CellData(index, i, j, i, j));
249  }
250  }
251  }
252 
253  // Process cells by increasing distance; new cells are appended to the corresponding distance bin, so they
254  // can overtake previously inserted but farther away cells
256  for (bin = inflation_cells_.begin(); bin != inflation_cells_.end(); ++bin)
257  {
258  for (int i = 0; i < bin->second.size(); ++i)
259  {
260  // process all cells at distance dist_bin.first
261  const CellData& cell = bin->second[i];
262 
263  unsigned int index = cell.index_;
264 
265  // ignore if already visited
266  if (seen_[index])
267  {
268  continue;
269  }
270 
271  seen_[index] = true;
272 
273  unsigned int mx = cell.x_;
274  unsigned int my = cell.y_;
275  unsigned int sx = cell.src_x_;
276  unsigned int sy = cell.src_y_;
277 
278  // assign the cost associated with the distance from an obstacle to the cell
279  unsigned char cost = costLookup(mx, my, sx, sy);
280  unsigned char old_cost = master_array[index];
281  if (old_cost != target_cell_value_ && old_cost == LETHAL_OBSTACLE && (inflate_unknown_ ? (cost > FREE_SPACE) : (cost >= INSCRIBED_INFLATED_OBSTACLE)))
282  return;
283 
284  if (old_cost != target_cell_value_)
285  {
287  master_grid.setCost(mx, my, cost);
288  else
289  master_grid.setCost(mx, my, std::max(old_cost, cost));
290  }
291 
292  // attempt to put the neighbors of the current cell onto the inflation list
293  if (mx > 0)
294  enqueue(index - 1, mx - 1, my, sx, sy);
295  if (my > 0)
296  enqueue(index - size_x, mx, my - 1, sx, sy);
297  if (mx < size_x - 1)
298  enqueue(index + 1, mx + 1, my, sx, sy);
299  if (my < size_y - 1)
300  enqueue(index + size_x, mx, my + 1, sx, sy);
301  }
302  }
303 
304  inflation_cells_.clear();
305 }
306 
316 inline void InflationLayer::enqueue(unsigned int index, unsigned int mx, unsigned int my,
317  unsigned int src_x, unsigned int src_y)
318 {
319  if (!seen_[index])
320  {
321  // we compute our distance table one cell further than the inflation radius dictates so we can make the check below
322  double distance = distanceLookup(mx, my, src_x, src_y);
323 
324  // we only want to put the cell in the list if it is within the inflation radius of the obstacle point
326  return;
327 
328  // push the cell data onto the inflation list and mark
329  inflation_cells_[distance].push_back(CellData(index, mx, my, src_x, src_y));
330  }
331 }
332 
334 {
335  if (cell_inflation_radius_ == 0)
336  return;
337 
338  // based on the inflation radius... compute distance and cost caches
340  {
341  deleteKernels();
342 
343  cached_costs_ = new unsigned char*[cell_inflation_radius_ + 2];
344  cached_distances_ = new double*[cell_inflation_radius_ + 2];
345 
346  for (unsigned int i = 0; i <= cell_inflation_radius_ + 1; ++i)
347  {
348  cached_costs_[i] = new unsigned char[cell_inflation_radius_ + 2];
349  cached_distances_[i] = new double[cell_inflation_radius_ + 2];
350  for (unsigned int j = 0; j <= cell_inflation_radius_ + 1; ++j)
351  {
352  cached_distances_[i][j] = hypot(i, j);
353  }
354  }
355 
357  }
358 
359  for (unsigned int i = 0; i <= cell_inflation_radius_ + 1; ++i)
360  {
361  for (unsigned int j = 0; j <= cell_inflation_radius_ + 1; ++j)
362  {
364  }
365  }
366 }
367 
369 {
370  if (cached_distances_ != NULL)
371  {
372  for (unsigned int i = 0; i <= cached_cell_inflation_radius_ + 1; ++i)
373  {
374  if (cached_distances_[i])
375  delete[] cached_distances_[i];
376  }
377  if (cached_distances_)
378  delete[] cached_distances_;
379  cached_distances_ = NULL;
380  }
381 
382  if (cached_costs_ != NULL)
383  {
384  for (unsigned int i = 0; i <= cached_cell_inflation_radius_ + 1; ++i)
385  {
386  if (cached_costs_[i])
387  delete[] cached_costs_[i];
388  }
389  delete[] cached_costs_;
390  cached_costs_ = NULL;
391  }
392 }
393 
394 void InflationLayer::setInflationParameters(double inflation_radius, double cost_scaling_factor)
395 {
396  if (weight_ != cost_scaling_factor || inflation_radius_ != inflation_radius)
397  {
398  // Lock here so that reconfiguring the inflation radius doesn't cause segfaults
399  // when accessing the cached arrays
400  boost::unique_lock < boost::recursive_mutex > lock(*inflation_access_);
401 
402  inflation_radius_ = inflation_radius;
404  weight_ = cost_scaling_factor;
405  need_reinflation_ = true;
406  computeCaches();
407  }
408 }
409 
410 } // namespace costmap_2d
costmap_2d::InflationLayer::use_footprint_
bool use_footprint_
Definition: inflation_layer.h:219
costmap_2d::InflationLayer::inflation_access_
boost::recursive_mutex * inflation_access_
Definition: inflation_layer.h:166
costmap_2d::InflationLayer::inflation_cells_
std::map< double, std::vector< CellData > > inflation_cells_
Definition: inflation_layer.h:223
costmap_2d::InflationLayer::cellDistance
unsigned int cellDistance(double world_dist)
Definition: inflation_layer.h:209
costmap_2d::InflationLayer::dsrv_
dynamic_reconfigure::Server< costmap_2d::InflationPluginConfig > * dsrv_
Definition: inflation_layer.h:232
costmap_2d::InflationLayer::distanceLookup
double distanceLookup(int mx, int my, int src_x, int src_y)
Lookup pre-computed distances.
Definition: inflation_layer.h:183
costmap_2d::InflationLayer::inflate_unknown_
bool inflate_unknown_
Definition: inflation_layer.h:172
costmap_2d::Layer::enabled_
bool enabled_
Definition: layer.h:176
costmap_2d::InflationLayer::cached_costs_
unsigned char ** cached_costs_
Definition: inflation_layer.h:228
costmap_2d::InflationLayer::dilation_cell_value_
unsigned char dilation_cell_value_
Definition: inflation_layer.h:218
costmap_2d::InflationLayer::inscribed_radius_
double inscribed_radius_
Definition: inflation_layer.h:170
std::vector
std::vector::size
T size(T... args)
costmap_2d::InflationLayer::costLookup
unsigned char costLookup(int mx, int my, int src_x, int src_y)
Lookup pre-computed costs.
Definition: inflation_layer.h:198
costmap_2d::INSCRIBED_INFLATED_OBSTACLE
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
Definition: cost_values.h:79
costmap_2d::InflationLayer::onInitialize
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization.
Definition: inflation_layer.cpp:78
costmap_2d::CellData::src_y_
unsigned int src_y_
Definition: inflation_layer.h:108
costmap_2d::InflationLayer::inflation_radius_
double inflation_radius_
Definition: inflation_layer.h:169
costmap_2d::NO_INFORMATION
static const unsigned char NO_INFORMATION
Definition: cost_values.h:77
costmap_2d::InflationLayer::updateCosts
virtual void updateCosts(costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Actually update the underlying costmap, only within the bounds calculated during UpdateBounds().
Definition: inflation_layer.cpp:195
costmap_2d::CellData
Storage for cell information used during obstacle inflation.
Definition: inflation_layer.h:90
costmap_2d::InflationLayer::target_cell_value_
unsigned char target_cell_value_
Definition: inflation_layer.h:218
costmap_2d::InflationLayer::computeCost
virtual unsigned char computeCost(double distance) const
Given a distance, compute a cost.
Definition: inflation_layer.h:140
costmap_2d::CellData::src_x_
unsigned int src_x_
Definition: inflation_layer.h:108
costmap_2d::Costmap2D
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.h:96
costmap_2d::Costmap2D::getCharMap
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
Definition: costmap_2d.cpp:197
costmap_2d::Layer::name_
std::string name_
Definition: layer.h:177
costmap_2d::Layer::current_
bool current_
Definition: layer.h:175
costmap_2d::LayeredCostmap::getInscribedRadius
double getInscribedRadius()
The radius of a circle centered at the origin of the robot which is just within all points and edges ...
Definition: layered_costmap.h:191
costmap_2d::Layer::layered_costmap_
LayeredCostmap * layered_costmap_
Definition: layer.h:174
algorithm
costmap_2d::InflationLayer::last_max_x_
double last_max_x_
Definition: inflation_layer.h:230
costmap_2d::InflationLayer::cached_distances_
double ** cached_distances_
Definition: inflation_layer.h:229
std::vector::push_back
T push_back(T... args)
costmap_2d::CellData::index_
unsigned int index_
Definition: inflation_layer.h:106
costmap_2d::InflationLayer
Definition: inflation_layer.h:111
costmap_2d::InflationLayer::need_reinflation_
bool need_reinflation_
Indicates that the entire costmap should be reinflated next time around.
Definition: inflation_layer.h:235
costmap_2d::InflationLayer::dilation_radius_
double dilation_radius_
Definition: inflation_layer.h:217
costmap_2d::InflationLayer::seen_size_
int seen_size_
Definition: inflation_layer.h:226
costmap_2d::Costmap2D::setCost
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
Set the cost of a cell in the costmap.
Definition: costmap_2d.cpp:212
costmap_2d::InflationLayer::reconfigureCB
void reconfigureCB(costmap_2d::InflationPluginConfig &config, uint32_t level)
Definition: inflation_layer.cpp:107
costmap_2d::InflationLayer::onFootprintChanged
virtual void onFootprintChanged()
LayeredCostmap calls this whenever the footprint there changes (via LayeredCostmap::setFootprint())....
Definition: inflation_layer.cpp:180
costmap_2d::InflationLayer::cached_cell_inflation_radius_
unsigned int cached_cell_inflation_radius_
Definition: inflation_layer.h:222
costmap_2d::InflationLayer::setInflationParameters
void setInflationParameters(double inflation_radius, double cost_scaling_factor)
Change the values of the inflation radius parameters.
Definition: inflation_layer.cpp:394
costmap_2d::InflationLayer::last_max_y_
double last_max_y_
Definition: inflation_layer.h:230
costmap_2d::Costmap2D::getSizeInCellsY
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:456
costmap_2d::LayeredCostmap::getFootprint
const std::vector< geometry_msgs::Point > & getFootprint()
Returns the latest footprint stored with setFootprint().
Definition: layered_costmap.h:177
inflation_layer.h
costmap_2d::LETHAL_OBSTACLE
static const unsigned char LETHAL_OBSTACLE
Definition: cost_values.h:78
distance
double distance(double x0, double y0, double x1, double y1)
Definition: costmap_math.h:58
costmap_2d::InflationLayer::resolution_
double resolution_
Definition: inflation_layer.h:168
std::map
costmap_math.h
costmap_2d::InflationLayer::enqueue
void enqueue(unsigned int index, unsigned int mx, unsigned int my, unsigned int src_x, unsigned int src_y)
Given an index of a cell in the costmap, place it into a list pending for obstacle inflation.
Definition: inflation_layer.cpp:316
costmap_2d::InflationLayer::InflationLayer
InflationLayer()
Definition: inflation_layer.cpp:54
costmap_2d::InflationLayer::last_min_x_
double last_min_x_
Definition: inflation_layer.h:230
costmap_2d::InflationLayer::last_min_y_
double last_min_y_
Definition: inflation_layer.h:230
std::min
T min(T... args)
costmap_2d::InflationLayer::cell_inflation_radius_
unsigned int cell_inflation_radius_
Definition: inflation_layer.h:221
footprint.h
costmap_2d::CellData::x_
unsigned int x_
Definition: inflation_layer.h:107
costmap_2d::InflationLayer::seen_
bool * seen_
Definition: inflation_layer.h:225
std
costmap_2d::InflationLayer::updateBounds
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
This is called by the LayeredCostmap to poll this plugin as to how much of the costmap it needs to up...
Definition: inflation_layer.cpp:145
costmap_2d::InflationLayer::computeCaches
void computeCaches()
Definition: inflation_layer.cpp:333
costmap_2d::CellData::y_
unsigned int y_
Definition: inflation_layer.h:107
costmap_2d::InflationLayer::weight_
double weight_
Definition: inflation_layer.h:171
costmap_2d::Costmap2D::getResolution
double getResolution() const
Accessor for the resolution of the costmap.
Definition: costmap_2d.cpp:481
costmap_2d::Layer
Definition: layer.h:84
costmap_2d::Costmap2D::getIndex
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
Definition: costmap_2d.h:215
costmap_2d::LayeredCostmap::getCostmap
Costmap2D * getCostmap()
Definition: layered_costmap.h:128
costmap_2d::FREE_SPACE
static const unsigned char FREE_SPACE
Definition: cost_values.h:80
costmap_2d::InflationLayer::deleteKernels
void deleteKernels()
Definition: inflation_layer.cpp:368
costmap_2d::Costmap2D::getSizeInCellsX
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:451
std::numeric_limits::max
T max(T... args)
costmap_2d
Definition: array_parser.h:37
costmap_2d::InflationLayer::matchSize
virtual void matchSize()
Implement this to make this layer match the size of the parent costmap.
Definition: inflation_layer.cpp:130