Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
costmap_2d::InflationLayer Class Reference

#include <inflation_layer.h>

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

Public Member Functions

virtual unsigned char computeCost (double distance) const
 Given a distance, compute a cost. More...
 
 InflationLayer ()
 
virtual bool isDiscretized ()
 
virtual void matchSize ()
 Implement this to make this layer match the size of the parent costmap. More...
 
virtual void onInitialize ()
 This is called at the end of initialize(). Override to implement subclass-specific initialization. More...
 
virtual void reset ()
 
void setInflationParameters (double inflation_radius, double cost_scaling_factor)
 Change the values of the inflation radius parameters. More...
 
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. More...
 
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(). More...
 
virtual ~InflationLayer ()
 
- Public Member Functions inherited from costmap_2d::Layer
virtual void activate ()
 Restart publishers if they've been stopped. More...
 
virtual void deactivate ()
 Stop publishers. More...
 
const std::vector< geometry_msgs::Point > & getFootprint () const
 Convenience function for layered_costmap_->getFootprint(). More...
 
std::string getName () const
 
void initialize (LayeredCostmap *parent, std::string name, tf::TransformListener *tf)
 
bool isCurrent () const
 Check to make sure all the data in the layer is up to date. If the layer is not up to date, then it may be unsafe to plan using the data from this layer, and the planner may need to know. More...
 
 Layer ()
 
virtual ~Layer ()
 

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. More...
 

Protected Attributes

bool inflate_unknown_
 
boost::recursive_mutex * inflation_access_
 
double inflation_radius_
 
double inscribed_radius_
 
double resolution_
 
double weight_
 
- Protected Attributes inherited from costmap_2d::Layer
bool current_
 
bool enabled_
 Currently this var is managed by subclasses. TODO: make this managed by this class and/or container class. More...
 
LayeredCostmaplayered_costmap_
 
std::string name_
 
tf::TransformListenertf_
 

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. More...
 
void deleteKernels ()
 
double distanceLookup (int mx, int my, int src_x, int src_y)
 Lookup pre-computed distances. More...
 
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. More...
 
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::map< double, std::vector< CellData > > inflation_cells_
 
double last_max_x_
 
double last_max_y_
 
double last_min_x_
 
double last_min_y_
 
bool need_reinflation_
 Indicates that the entire costmap should be reinflated next time around. More...
 
bool * seen_
 
int seen_size_
 

Detailed Description

Definition at line 75 of file inflation_layer.h.

Constructor & Destructor Documentation

costmap_2d::InflationLayer::InflationLayer ( )

Definition at line 54 of file inflation_layer.cpp.

virtual costmap_2d::InflationLayer::~InflationLayer ( )
inlinevirtual

Definition at line 80 of file inflation_layer.h.

Member Function Documentation

unsigned int costmap_2d::InflationLayer::cellDistance ( double  world_dist)
inlineprivate

Definition at line 171 of file inflation_layer.h.

void costmap_2d::InflationLayer::computeCaches ( )
private

Definition at line 306 of file inflation_layer.cpp.

virtual unsigned char costmap_2d::InflationLayer::computeCost ( double  distance) const
inlinevirtual

Given a distance, compute a cost.

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

Definition at line 102 of file inflation_layer.h.

unsigned char costmap_2d::InflationLayer::costLookup ( int  mx,
int  my,
int  src_x,
int  src_y 
)
inlineprivate

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 160 of file inflation_layer.h.

void costmap_2d::InflationLayer::deleteKernels ( )
private

Definition at line 341 of file inflation_layer.cpp.

double costmap_2d::InflationLayer::distanceLookup ( int  mx,
int  my,
int  src_x,
int  src_y 
)
inlineprivate

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 145 of file inflation_layer.h.

void costmap_2d::InflationLayer::enqueue ( unsigned int  index,
unsigned int  mx,
unsigned int  my,
unsigned int  src_x,
unsigned int  src_y 
)
inlineprivate

Given an index of a cell in the costmap, place it into a list pending 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 289 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 ( )
inlinevirtual

Definition at line 91 of file inflation_layer.h.

void costmap_2d::InflationLayer::matchSize ( )
virtual

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

Reimplemented from costmap_2d::Layer.

Definition at line 112 of file inflation_layer.cpp.

void costmap_2d::InflationLayer::onFootprintChanged ( )
protectedvirtual

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 162 of file inflation_layer.cpp.

void costmap_2d::InflationLayer::onInitialize ( )
virtual

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 72 of file inflation_layer.cpp.

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

Definition at line 101 of file inflation_layer.cpp.

virtual void costmap_2d::InflationLayer::reset ( )
inlinevirtual

Reimplemented from costmap_2d::Layer.

Definition at line 97 of file inflation_layer.h.

void costmap_2d::InflationLayer::setInflationParameters ( double  inflation_radius,
double  cost_scaling_factor 
)

Change the values of the inflation radius parameters.

Parameters
inflation_radiusThe new inflation radius
cost_scaling_factorThe new weight

Definition at line 367 of file inflation_layer.cpp.

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 127 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 174 of file inflation_layer.cpp.

Member Data Documentation

unsigned int costmap_2d::InflationLayer::cached_cell_inflation_radius_
private

Definition at line 180 of file inflation_layer.h.

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

Definition at line 186 of file inflation_layer.h.

double** costmap_2d::InflationLayer::cached_distances_
private

Definition at line 187 of file inflation_layer.h.

unsigned int costmap_2d::InflationLayer::cell_inflation_radius_
private

Definition at line 179 of file inflation_layer.h.

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

Definition at line 190 of file inflation_layer.h.

bool costmap_2d::InflationLayer::inflate_unknown_
protected

Definition at line 134 of file inflation_layer.h.

boost::recursive_mutex* costmap_2d::InflationLayer::inflation_access_
protected

Definition at line 128 of file inflation_layer.h.

std::map<double, std::vector<CellData> > costmap_2d::InflationLayer::inflation_cells_
private

Definition at line 181 of file inflation_layer.h.

double costmap_2d::InflationLayer::inflation_radius_
protected

Definition at line 131 of file inflation_layer.h.

double costmap_2d::InflationLayer::inscribed_radius_
protected

Definition at line 132 of file inflation_layer.h.

double costmap_2d::InflationLayer::last_max_x_
private

Definition at line 188 of file inflation_layer.h.

double costmap_2d::InflationLayer::last_max_y_
private

Definition at line 188 of file inflation_layer.h.

double costmap_2d::InflationLayer::last_min_x_
private

Definition at line 188 of file inflation_layer.h.

double costmap_2d::InflationLayer::last_min_y_
private

Definition at line 188 of file inflation_layer.h.

bool costmap_2d::InflationLayer::need_reinflation_
private

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

Definition at line 193 of file inflation_layer.h.

double costmap_2d::InflationLayer::resolution_
protected

Definition at line 130 of file inflation_layer.h.

bool* costmap_2d::InflationLayer::seen_
private

Definition at line 183 of file inflation_layer.h.

int costmap_2d::InflationLayer::seen_size_
private

Definition at line 184 of file inflation_layer.h.

double costmap_2d::InflationLayer::weight_
protected

Definition at line 133 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 Sun Mar 3 2019 03:44:17