Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
costmap_2d::InflationLayer Class Reference

#include <inflation_layer.h>

Inheritance diagram for costmap_2d::InflationLayer:
Inheritance graph
[legend]

List of all members.

Public Member Functions

unsigned char computeCost (double distance) const
 Given a distance, compute a cost.
 InflationLayer ()
virtual bool isDiscretized ()
virtual void matchSize ()
 Implement this to make this layer match the size of the parent costmap.
virtual void onInitialize ()
 This is called at the end of initialize(). Override to implement subclass-specific initialization.
virtual void reset ()
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 update. Each layer can increase the size of this bounds.
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().
virtual ~InflationLayer ()

Protected Member Functions

virtual void onFootprintChanged ()
 LayeredCostmap calls this whenever the footprint there changes (via LayeredCostmap::setFootprint()). Override to be notified of changes to the robot's footprint.

Protected Attributes

boost::shared_mutex * access_

Private Member Functions

unsigned int cellDistance (double world_dist)
void computeCaches ()
unsigned char costLookup (int mx, int my, int src_x, int src_y)
 Lookup pre-computed costs.
void deleteKernels ()
double distanceLookup (int mx, int my, int src_x, int src_y)
 Lookup pre-computed distances.
void enqueue (unsigned char *grid, 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 priority queue for obstacle inflation.
void inflate_area (int min_i, int min_j, int max_i, int max_j, unsigned char *master_grid)
void reconfigureCB (costmap_2d::InflationPluginConfig &config, uint32_t level)

Private Attributes

unsigned int cached_cell_inflation_radius_
unsigned char ** cached_costs_
double ** cached_distances_
unsigned int cell_inflation_radius_
dynamic_reconfigure::Server
< costmap_2d::InflationPluginConfig > * 
dsrv_
std::priority_queue< CellDatainflation_queue_
double inflation_radius_
double inscribed_radius_
bool need_reinflation_
 Indicates that the entire costmap should be reinflated next time around.
double resolution_
bool * seen_
double weight_

Detailed Description

Definition at line 86 of file inflation_layer.h.


Constructor & Destructor Documentation

Definition at line 52 of file inflation_layer.cpp.

virtual costmap_2d::InflationLayer::~InflationLayer ( ) [inline, virtual]

Definition at line 91 of file inflation_layer.h.


Member Function Documentation

unsigned int costmap_2d::InflationLayer::cellDistance ( double  world_dist) [inline, private]

Definition at line 169 of file inflation_layer.h.

Definition at line 253 of file inflation_layer.cpp.

unsigned char costmap_2d::InflationLayer::computeCost ( double  distance) const [inline]

Given a distance, compute a cost.

Parameters:
distanceThe distance from an obstacle in cells
Returns:
A cost value for the distance

Definition at line 113 of file inflation_layer.h.

unsigned char costmap_2d::InflationLayer::costLookup ( int  mx,
int  my,
int  src_x,
int  src_y 
) [inline, private]

Lookup pre-computed costs.

Parameters:
mxThe x coordinate of the current cell
myThe y coordinate of the current cell
src_xThe x coordinate of the source cell
src_yThe y coordinate of the source cell
Returns:

Definition at line 158 of file inflation_layer.h.

Definition at line 289 of file inflation_layer.cpp.

double costmap_2d::InflationLayer::distanceLookup ( int  mx,
int  my,
int  src_x,
int  src_y 
) [inline, private]

Lookup pre-computed distances.

Parameters:
mxThe x coordinate of the current cell
myThe y coordinate of the current cell
src_xThe x coordinate of the source cell
src_yThe y coordinate of the source cell
Returns:

Definition at line 143 of file inflation_layer.h.

void costmap_2d::InflationLayer::enqueue ( unsigned char *  grid,
unsigned int  index,
unsigned int  mx,
unsigned int  my,
unsigned int  src_x,
unsigned int  src_y 
) [inline, private]

Given an index of a cell in the costmap, place it into a priority queue for obstacle inflation.

Parameters:
gridThe costmap
indexThe index of the cell
mxThe x coordinate of the cell (can be computed from the index, but saves time to store it)
myThe y coordinate of the cell (can be computed from the index, but saves time to store it)
src_xThe x index of the obstacle point inflation started at
src_yThe y index of the obstacle point inflation started at

Definition at line 224 of file inflation_layer.cpp.

void costmap_2d::InflationLayer::inflate_area ( int  min_i,
int  min_j,
int  max_i,
int  max_j,
unsigned char *  master_grid 
) [private]
virtual bool costmap_2d::InflationLayer::isDiscretized ( ) [inline, virtual]

Definition at line 102 of file inflation_layer.h.

Implement this to make this layer match the size of the parent costmap.

Reimplemented from costmap_2d::Layer.

Definition at line 106 of file inflation_layer.cpp.

void costmap_2d::InflationLayer::onFootprintChanged ( ) [protected, virtual]

LayeredCostmap calls this whenever the footprint there changes (via LayeredCostmap::setFootprint()). Override to be notified of changes to the robot's footprint.

Reimplemented from costmap_2d::Layer.

Definition at line 136 of file inflation_layer.cpp.

This is called at the end of initialize(). Override to implement subclass-specific initialization.

tf_, name_, and layered_costmap_ will all be set already when this is called.

Reimplemented from costmap_2d::Layer.

Definition at line 62 of file inflation_layer.cpp.

void costmap_2d::InflationLayer::reconfigureCB ( costmap_2d::InflationPluginConfig &  config,
uint32_t  level 
) [private]

Definition at line 89 of file inflation_layer.cpp.

virtual void costmap_2d::InflationLayer::reset ( ) [inline, virtual]

Reimplemented from costmap_2d::Layer.

Definition at line 108 of file inflation_layer.h.

void costmap_2d::InflationLayer::updateBounds ( double  robot_x,
double  robot_y,
double  robot_yaw,
double *  min_x,
double *  min_y,
double *  max_x,
double *  max_y 
) [virtual]

This is called by the LayeredCostmap to poll this plugin as to how much of the costmap it needs to update. Each layer can increase the size of this bounds.

For more details, see "Layered Costmaps for Context-Sensitive Navigation", by Lu et. Al, IROS 2014.

Reimplemented from costmap_2d::Layer.

Definition at line 120 of file inflation_layer.cpp.

void costmap_2d::InflationLayer::updateCosts ( costmap_2d::Costmap2D master_grid,
int  min_i,
int  min_j,
int  max_i,
int  max_j 
) [virtual]

Actually update the underlying costmap, only within the bounds calculated during UpdateBounds().

Reimplemented from costmap_2d::Layer.

Definition at line 147 of file inflation_layer.cpp.


Member Data Documentation

boost::shared_mutex* costmap_2d::InflationLayer::access_ [protected]

Definition at line 132 of file inflation_layer.h.

Definition at line 179 of file inflation_layer.h.

unsigned char** costmap_2d::InflationLayer::cached_costs_ [private]

Definition at line 186 of file inflation_layer.h.

Definition at line 187 of file inflation_layer.h.

Definition at line 178 of file inflation_layer.h.

dynamic_reconfigure::Server<costmap_2d::InflationPluginConfig>* costmap_2d::InflationLayer::dsrv_ [private]

Definition at line 189 of file inflation_layer.h.

Definition at line 180 of file inflation_layer.h.

Definition at line 177 of file inflation_layer.h.

Definition at line 177 of file inflation_layer.h.

Indicates that the entire costmap should be reinflated next time around.

Definition at line 192 of file inflation_layer.h.

Definition at line 182 of file inflation_layer.h.

Definition at line 184 of file inflation_layer.h.

Definition at line 177 of file inflation_layer.h.


The documentation for this class was generated from the following files:


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Thu Aug 27 2015 14:06:55