Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
inflation_layer.hpp
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 #ifndef NAV2_COSTMAP_2D__INFLATION_LAYER_HPP_
39 #define NAV2_COSTMAP_2D__INFLATION_LAYER_HPP_
40 
41 #include <map>
42 #include <vector>
43 #include <mutex>
44 #include <memory>
45 #include <string>
46 
47 #include "rclcpp/rclcpp.hpp"
48 #include "nav2_costmap_2d/layer.hpp"
49 #include "nav2_costmap_2d/layered_costmap.hpp"
50 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
51 
52 namespace nav2_costmap_2d
53 {
58 class CellData
59 {
60 public:
69  CellData(unsigned int x, unsigned int y, unsigned int sx, unsigned int sy)
70  : x_(x), y_(y), src_x_(sx), src_y_(sy)
71  {
72  }
73  unsigned int x_, y_;
74  unsigned int src_x_, src_y_;
75 };
76 
82 class InflationLayer : public Layer
83 {
84 public:
89 
94 
98  void onInitialize() override;
99 
110  void updateBounds(
111  double robot_x, double robot_y, double robot_yaw, double * min_x,
112  double * min_y,
113  double * max_x,
114  double * max_y) override;
123  void updateCosts(
124  nav2_costmap_2d::Costmap2D & master_grid,
125  int min_i, int min_j, int max_i, int max_j) override;
126 
130  void matchSize() override;
131 
135  bool isClearable() override {return false;}
136 
140  void reset() override
141  {
142  matchSize();
143  current_ = false;
144  }
145 
149  inline unsigned char computeCost(double distance) const
150  {
151  unsigned char cost = 0;
152  if (distance == 0) {
153  cost = LETHAL_OBSTACLE;
154  } else if (distance * resolution_ <= inscribed_radius_) {
155  cost = INSCRIBED_INFLATED_OBSTACLE;
156  } else {
157  // make sure cost falls off by Euclidean distance
158  double factor =
159  exp(-1.0 * cost_scaling_factor_ * (distance * resolution_ - inscribed_radius_));
160  cost = static_cast<unsigned char>((INSCRIBED_INFLATED_OBSTACLE - 1) * factor);
161  }
162  return cost;
163  }
164 
165  static std::shared_ptr<nav2_costmap_2d::InflationLayer> getInflationLayer(
166  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> & costmap_ros,
167  const std::string layer_name = "")
168  {
169  const auto layered_costmap = costmap_ros->getLayeredCostmap();
170  for (auto layer = layered_costmap->getPlugins()->begin();
171  layer != layered_costmap->getPlugins()->end();
172  ++layer)
173  {
174  auto inflation_layer = std::dynamic_pointer_cast<nav2_costmap_2d::InflationLayer>(*layer);
175  if (inflation_layer) {
176  if (layer_name.empty() || inflation_layer->getName() == layer_name) {
177  return inflation_layer;
178  }
179  }
180  }
181  return nullptr;
182  }
183 
184  // Provide a typedef to ease future code maintenance
185  typedef std::recursive_mutex mutex_t;
186 
190  mutex_t * getMutex()
191  {
192  return access_;
193  }
194 
195  double getCostScalingFactor()
196  {
197  return cost_scaling_factor_;
198  }
199 
200  double getInflationRadius()
201  {
202  return inflation_radius_;
203  }
204 
205 protected:
209  void onFootprintChanged() override;
210 
219  inline double distanceLookup(
220  unsigned int mx, unsigned int my, unsigned int src_x,
221  unsigned int src_y)
222  {
223  unsigned int dx = (mx > src_x) ? mx - src_x : src_x - mx;
224  unsigned int dy = (my > src_y) ? my - src_y : src_y - my;
225  return cached_distances_[dx * cache_length_ + dy];
226  }
227 
236  inline unsigned char costLookup(
237  unsigned int mx, unsigned int my, unsigned int src_x,
238  unsigned int src_y)
239  {
240  unsigned int dx = (mx > src_x) ? mx - src_x : src_x - mx;
241  unsigned int dy = (my > src_y) ? my - src_y : src_y - my;
242  return cached_costs_[dx * cache_length_ + dy];
243  }
244 
248  void computeCaches();
249 
254 
258  unsigned int cellDistance(double world_dist)
259  {
260  return layered_costmap_->getCostmap()->cellDistance(world_dist);
261  }
262 
266  inline void enqueue(
267  unsigned int index, unsigned int mx, unsigned int my,
268  unsigned int src_x, unsigned int src_y);
269 
274  rcl_interfaces::msg::SetParametersResult
275  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
276 
277  double inflation_radius_, inscribed_radius_, cost_scaling_factor_;
278  bool inflate_unknown_, inflate_around_unknown_;
279  unsigned int cell_inflation_radius_;
280  unsigned int cached_cell_inflation_radius_;
281  std::vector<std::vector<CellData>> inflation_cells_;
282 
283  double resolution_;
284 
285  std::vector<bool> seen_;
286 
287  std::vector<unsigned char> cached_costs_;
288  std::vector<double> cached_distances_;
289  std::vector<std::vector<int>> distance_matrix_;
290  unsigned int cache_length_;
291  double last_min_x_, last_min_y_, last_max_x_, last_max_y_;
292 
293  // Indicates that the entire costmap should be reinflated next time around.
294  bool need_reinflation_;
295  mutex_t * access_;
296  // Dynamic parameters handler
297  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
298 };
299 
300 } // namespace nav2_costmap_2d
301 
302 #endif // NAV2_COSTMAP_2D__INFLATION_LAYER_HPP_
Storage for cell information used during obstacle inflation.
CellData(unsigned int x, unsigned int y, unsigned int sx, unsigned int sy)
Constructor for a CellData objects.
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
unsigned int cellDistance(double world_dist)
Given distance in the world... convert it to cells.
Definition: costmap_2d.cpp:253
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 reset() override
Reset this costmap.
void matchSize() override
Match the size of the master costmap.
void onFootprintChanged() override
Process updates on footprint changes to the inflation layer.
bool isClearable() override
If clearing operations should be processed on this layer or not.
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
Costmap2D * getCostmap()
Get the costmap pointer to the master costmap.