inflation_layer.h
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 #ifndef COSTMAP_2D_INFLATION_LAYER_H_
39 #define COSTMAP_2D_INFLATION_LAYER_H_
40 
41 #include <ros/ros.h>
42 #include <costmap_2d/layer.h>
44 #include <costmap_2d/InflationPluginConfig.h>
45 #include <dynamic_reconfigure/server.h>
46 #include <boost/thread.hpp>
47 
48 namespace costmap_2d
49 {
54 class CellData
55 {
56 public:
66  CellData(double i, unsigned int x, unsigned int y, unsigned int sx, unsigned int sy) :
67  index_(i), x_(x), y_(y), src_x_(sx), src_y_(sy)
68  {
69  }
70  unsigned int index_;
71  unsigned int x_, y_;
72  unsigned int src_x_, src_y_;
73 };
74 
75 class InflationLayer : public Layer
76 {
77 public:
79 
80  virtual ~InflationLayer()
81  {
82  deleteKernels();
83  if (dsrv_)
84  delete dsrv_;
85  if (seen_)
86  delete[] seen_;
87  }
88 
89  virtual void onInitialize();
90  virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y,
91  double* max_x, double* max_y);
92  virtual void updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j);
93  virtual bool isDiscretized()
94  {
95  return true;
96  }
97  virtual void matchSize();
98 
99  virtual void reset() { onInitialize(); }
100 
104  virtual inline unsigned char computeCost(double distance) const
105  {
106  unsigned char cost = 0;
107  if (distance == 0)
109  else if (distance * resolution_ <= inscribed_radius_)
111  else
112  {
113  // make sure cost falls off by Euclidean distance
114  double euclidean_distance = distance * resolution_;
115  double factor = exp(-1.0 * weight_ * (euclidean_distance - inscribed_radius_));
116  cost = (unsigned char)((INSCRIBED_INFLATED_OBSTACLE - 1) * factor);
117  }
118  return cost;
119  }
120 
126  void setInflationParameters(double inflation_radius, double cost_scaling_factor);
127 
128 protected:
129  virtual void onFootprintChanged();
130  boost::recursive_mutex* inflation_access_;
131 
132  double resolution_;
133  double inflation_radius_;
134  double inscribed_radius_;
135  double weight_;
136  bool inflate_unknown_;
137 
138 private:
147  inline double distanceLookup(int mx, int my, int src_x, int src_y)
148  {
149  unsigned int dx = abs(mx - src_x);
150  unsigned int dy = abs(my - src_y);
151  return cached_distances_[dx][dy];
152  }
153 
162  inline unsigned char costLookup(int mx, int my, int src_x, int src_y)
163  {
164  unsigned int dx = abs(mx - src_x);
165  unsigned int dy = abs(my - src_y);
166  return cached_costs_[dx][dy];
167  }
168 
171  void inflate_area(int min_i, int min_j, int max_i, int max_j, unsigned char* master_grid);
172 
173  unsigned int cellDistance(double world_dist)
174  {
175  return layered_costmap_->getCostmap()->cellDistance(world_dist);
176  }
177 
178  inline void enqueue(unsigned int index, unsigned int mx, unsigned int my,
179  unsigned int src_x, unsigned int src_y);
180 
181  unsigned int cell_inflation_radius_;
182  unsigned int cached_cell_inflation_radius_;
183  std::map<double, std::vector<CellData> > inflation_cells_;
184 
185  bool* seen_;
186  int seen_size_;
187 
188  unsigned char** cached_costs_;
189  double** cached_distances_;
191 
192  dynamic_reconfigure::Server<costmap_2d::InflationPluginConfig> *dsrv_;
193  void reconfigureCB(costmap_2d::InflationPluginConfig &config, uint32_t level);
194 
195  bool need_reinflation_;
196 };
197 
198 } // namespace costmap_2d
199 
200 #endif // COSTMAP_2D_INFLATION_LAYER_H_
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:219
costmap_2d::InflationLayer::isDiscretized
virtual bool isDiscretized()
Definition: inflation_layer.h:129
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:228
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::InflationLayer::cached_costs_
unsigned char ** cached_costs_
Definition: inflation_layer.h:224
costmap_2d::InflationLayer::inscribed_radius_
double inscribed_radius_
Definition: inflation_layer.h:170
costmap_2d::InflationLayer::inflate_area
void inflate_area(int min_i, int min_j, int max_i, int max_j, unsigned char *master_grid)
ros.h
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::~InflationLayer
virtual ~InflationLayer()
Definition: inflation_layer.h:116
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:74
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::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:176
layered_costmap.h
layer.h
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::Layer::layered_costmap_
LayeredCostmap * layered_costmap_
Definition: layer.h:174
costmap_2d::InflationLayer::last_max_x_
double last_max_x_
Definition: inflation_layer.h:226
costmap_2d::InflationLayer::cached_distances_
double ** cached_distances_
Definition: inflation_layer.h:225
costmap_2d::CellData::index_
unsigned int index_
Definition: inflation_layer.h:106
costmap_2d::InflationLayer::need_reinflation_
bool need_reinflation_
Indicates that the entire costmap should be reinflated next time around.
Definition: inflation_layer.h:231
costmap_2d::CellData::CellData
CellData(double i, unsigned int x, unsigned int y, unsigned int sx, unsigned int sy)
Constructor for a CellData objects.
Definition: inflation_layer.h:102
costmap_2d::InflationLayer::seen_size_
int seen_size_
Definition: inflation_layer.h:222
costmap_2d::InflationLayer::reconfigureCB
void reconfigureCB(costmap_2d::InflationPluginConfig &config, uint32_t level)
Definition: inflation_layer.cpp:103
costmap_2d::InflationLayer::onFootprintChanged
virtual void onFootprintChanged()
LayeredCostmap calls this whenever the footprint there changes (via LayeredCostmap::setFootprint())....
Definition: inflation_layer.cpp:164
costmap_2d::InflationLayer::cached_cell_inflation_radius_
unsigned int cached_cell_inflation_radius_
Definition: inflation_layer.h:218
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:369
costmap_2d::InflationLayer::last_max_y_
double last_max_y_
Definition: inflation_layer.h:226
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
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:291
costmap_2d::InflationLayer::InflationLayer
InflationLayer()
Definition: inflation_layer.cpp:54
costmap_2d::InflationLayer::last_min_x_
double last_min_x_
Definition: inflation_layer.h:226
costmap_2d::InflationLayer::last_min_y_
double last_min_y_
Definition: inflation_layer.h:226
costmap_2d::InflationLayer::cell_inflation_radius_
unsigned int cell_inflation_radius_
Definition: inflation_layer.h:217
costmap_2d::Costmap2D::cellDistance
unsigned int cellDistance(double world_dist)
Given distance in the world... convert it to cells.
Definition: costmap_2d.cpp:181
costmap_2d::CellData::x_
unsigned int x_
Definition: inflation_layer.h:107
costmap_2d::InflationLayer::seen_
bool * seen_
Definition: inflation_layer.h:221
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:129
costmap_2d::InflationLayer::computeCaches
void computeCaches()
Definition: inflation_layer.cpp:308
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::LayeredCostmap::getCostmap
Costmap2D * getCostmap()
Definition: layered_costmap.h:128
costmap_2d::InflationLayer::deleteKernels
void deleteKernels()
Definition: inflation_layer.cpp:343
costmap_2d::InflationLayer::reset
virtual void reset()
Definition: inflation_layer.h:135
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:114


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17