Nav2 Navigation Stack - humble  humble
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 
45 #include "rclcpp/rclcpp.hpp"
46 #include "nav2_costmap_2d/layer.hpp"
47 #include "nav2_costmap_2d/layered_costmap.hpp"
48 
49 namespace nav2_costmap_2d
50 {
55 class CellData
56 {
57 public:
67  CellData(double i, unsigned int x, unsigned int y, unsigned int sx, unsigned int sy)
68  : index_(static_cast<unsigned int>(i)), x_(x), y_(y), src_x_(sx), src_y_(sy)
69  {
70  }
71  unsigned int index_;
72  unsigned int x_, y_;
73  unsigned int src_x_, src_y_;
74 };
75 
81 class InflationLayer : public Layer
82 {
83 public:
88 
93 
97  void onInitialize() override;
98 
109  void updateBounds(
110  double robot_x, double robot_y, double robot_yaw, double * min_x,
111  double * min_y,
112  double * max_x,
113  double * max_y) override;
122  void updateCosts(
123  nav2_costmap_2d::Costmap2D & master_grid,
124  int min_i, int min_j, int max_i, int max_j) override;
125 
129  void matchSize() override;
130 
134  virtual bool isClearable() override {return false;}
135 
139  void reset() override
140  {
141  matchSize();
142  current_ = false;
143  }
144 
148  inline unsigned char computeCost(double distance) const
149  {
150  unsigned char cost = 0;
151  if (distance == 0) {
152  cost = LETHAL_OBSTACLE;
153  } else if (distance * resolution_ <= inscribed_radius_) {
154  cost = INSCRIBED_INFLATED_OBSTACLE;
155  } else {
156  // make sure cost falls off by Euclidean distance
157  double factor =
158  exp(-1.0 * cost_scaling_factor_ * (distance * resolution_ - inscribed_radius_));
159  cost = static_cast<unsigned char>((INSCRIBED_INFLATED_OBSTACLE - 1) * factor);
160  }
161  return cost;
162  }
163 
164  // Provide a typedef to ease future code maintenance
165  typedef std::recursive_mutex mutex_t;
166 
170  mutex_t * getMutex()
171  {
172  return access_;
173  }
174 
175 protected:
179  void onFootprintChanged() override;
180 
189  inline double distanceLookup(
190  unsigned int mx, unsigned int my, unsigned int src_x,
191  unsigned int src_y)
192  {
193  unsigned int dx = (mx > src_x) ? mx - src_x : src_x - mx;
194  unsigned int dy = (my > src_y) ? my - src_y : src_y - my;
195  return cached_distances_[dx * cache_length_ + dy];
196  }
197 
206  inline unsigned char costLookup(
207  unsigned int mx, unsigned int my, unsigned int src_x,
208  unsigned int src_y)
209  {
210  unsigned int dx = (mx > src_x) ? mx - src_x : src_x - mx;
211  unsigned int dy = (my > src_y) ? my - src_y : src_y - my;
212  return cached_costs_[dx * cache_length_ + dy];
213  }
214 
218  void computeCaches();
219 
224 
228  unsigned int cellDistance(double world_dist)
229  {
230  return layered_costmap_->getCostmap()->cellDistance(world_dist);
231  }
232 
236  inline void enqueue(
237  unsigned int index, unsigned int mx, unsigned int my,
238  unsigned int src_x, unsigned int src_y);
239 
244  rcl_interfaces::msg::SetParametersResult
245  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
246 
247  double inflation_radius_, inscribed_radius_, cost_scaling_factor_;
248  bool inflate_unknown_, inflate_around_unknown_;
249  unsigned int cell_inflation_radius_;
250  unsigned int cached_cell_inflation_radius_;
251  std::vector<std::vector<CellData>> inflation_cells_;
252 
253  double resolution_;
254 
255  std::vector<bool> seen_;
256 
257  std::vector<unsigned char> cached_costs_;
258  std::vector<double> cached_distances_;
259  std::vector<std::vector<int>> distance_matrix_;
260  unsigned int cache_length_;
261  double last_min_x_, last_min_y_, last_max_x_, last_max_y_;
262 
263  // Indicates that the entire costmap should be reinflated next time around.
264  bool need_reinflation_;
265  mutex_t * access_;
266  // Dynamic parameters handler
267  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
268 };
269 
270 } // namespace nav2_costmap_2d
271 
272 #endif // NAV2_COSTMAP_2D__INFLATION_LAYER_HPP_
Storage for cell information used during obstacle inflation.
CellData(double i, 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:68
unsigned int cellDistance(double world_dist)
Given distance in the world... convert it to cells.
Definition: costmap_2d.cpp:255
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.
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 inforamtion.
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.
virtual bool isClearable() override
If clearing operations should be processed on this layer or not.
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.