Go to the documentation of this file.
   42 #include <boost/thread.hpp> 
   56   , inflation_radius_(0)
 
   57   , inscribed_radius_(0)
 
   59   , inflate_unknown_(false)
 
   60   , cell_inflation_radius_(0)
 
   61   , cached_cell_inflation_radius_(0)
 
   65   , cached_distances_(NULL)
 
   66   , last_min_x_(-
std::numeric_limits<float>::max())
 
   67   , last_min_y_(-
std::numeric_limits<float>::max())
 
   68   , last_max_x_(
std::numeric_limits<float>::max())
 
   69   , last_max_y_(
std::numeric_limits<float>::max())
 
   86     dynamic_reconfigure::Server<costmap_2d::InflationPluginConfig>::CallbackType cb =
 
   87         [
this](
auto& config, 
auto level){ 
reconfigureCB(config, level); };
 
   90       dsrv_->clearCallback();
 
   91       dsrv_->setCallback(cb);
 
   96       dsrv_->setCallback(cb);
 
  130                                            double* min_y, 
double* max_x, 
double* max_y)
 
  141     *min_x = -std::numeric_limits<float>::max();
 
  142     *min_y = -std::numeric_limits<float>::max();
 
  143     *max_x = std::numeric_limits<float>::max();
 
  144     *max_y = std::numeric_limits<float>::max();
 
  171   ROS_DEBUG(
"InflationLayer::onFootprintChanged(): num footprint points: %lu," 
  172             " inscribed_radius_ = %.3f, inflation_radius_ = %.3f",
 
  185   unsigned char* master_array = master_grid.
getCharMap();
 
  189     ROS_WARN(
"InflationLayer::updateCosts(): seen_ array is NULL");
 
  195     ROS_WARN(
"InflationLayer::updateCosts(): seen_ array size is wrong");
 
  200   memset(
seen_, 
false, size_x * size_y * 
sizeof(
bool));
 
  211   min_i = std::max(0, min_i);
 
  212   min_j = std::max(0, min_j);
 
  213   max_i = std::min(
int(size_x), max_i);
 
  214   max_j = std::min(
int(size_y), max_j);
 
  221   for (
int j = min_j; j < max_j; j++)
 
  223     for (
int i = min_i; i < max_i; i++)
 
  225       int index = master_grid.
getIndex(i, j);
 
  226       unsigned char cost = master_array[index];
 
  229         obs_bin.push_back(
CellData(index, i, j, i, j));
 
  236   std::map<double, std::vector<CellData> >::iterator bin;
 
  239     for (
int i = 0; i < bin->second.size(); ++i)
 
  242       const CellData& cell = bin->second[i];
 
  244       unsigned int index = cell.
index_;
 
  254       unsigned int mx = cell.
x_;
 
  255       unsigned int my = cell.
y_;
 
  256       unsigned int sx = cell.
src_x_;
 
  257       unsigned int sy = cell.
src_y_;
 
  260       unsigned char cost = 
costLookup(mx, my, sx, sy);
 
  261       unsigned char old_cost = master_array[index];
 
  263         master_array[index] = cost;
 
  265         master_array[index] = std::max(old_cost, cost);
 
  269         enqueue(index - 1, mx - 1, my, sx, sy);
 
  271         enqueue(index - size_x, mx, my - 1, sx, sy);
 
  273         enqueue(index + 1, mx + 1, my, sx, sy);
 
  275         enqueue(index + size_x, mx, my + 1, sx, sy);
 
  292                                     unsigned int src_x, 
unsigned int src_y)
 
  
boost::recursive_mutex * inflation_access_
 
std::map< double, std::vector< CellData > > inflation_cells_
 
unsigned int cellDistance(double world_dist)
 
dynamic_reconfigure::Server< costmap_2d::InflationPluginConfig > * dsrv_
 
double distanceLookup(int mx, int my, int src_x, int src_y)
Lookup pre-computed distances.
 
unsigned char ** cached_costs_
 
unsigned char costLookup(int mx, int my, int src_x, int src_y)
Lookup pre-computed costs.
 
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
 
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization.
 
static const unsigned char NO_INFORMATION
 
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().
 
Storage for cell information used during obstacle inflation.
 
virtual unsigned char computeCost(double distance) const
Given a distance, compute a cost.
 
A 2D costmap provides a mapping between points in the world and their associated "costs".
 
unsigned char * getCharMap() const
Will return a pointer to the underlying unsigned char array used as the costmap.
 
double getInscribedRadius()
The radius of a circle centered at the origin of the robot which is just within all points and edges ...
 
LayeredCostmap * layered_costmap_
 
double ** cached_distances_
 
bool need_reinflation_
Indicates that the entire costmap should be reinflated next time around.
 
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
 
void reconfigureCB(costmap_2d::InflationPluginConfig &config, uint32_t level)
 
virtual void onFootprintChanged()
LayeredCostmap calls this whenever the footprint there changes (via LayeredCostmap::setFootprint())....
 
unsigned int cached_cell_inflation_radius_
 
void setInflationParameters(double inflation_radius, double cost_scaling_factor)
Change the values of the inflation radius parameters.
 
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
 
#define ROS_ASSERT_MSG(cond,...)
 
const std::vector< geometry_msgs::Point > & getFootprint()
Returns the latest footprint stored with setFootprint().
 
static const unsigned char LETHAL_OBSTACLE
 
double distance(double x0, double y0, double x1, double y1)
 
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.
 
unsigned int cell_inflation_radius_
 
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...
 
double getResolution() const
Accessor for the resolution of the costmap.
 
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
 
static const unsigned char FREE_SPACE
 
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
 
virtual void matchSize()
Implement this to make this layer match the size of the parent costmap.
 
costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:17