#include <inflation_layer.h>
|
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 () |
|
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...
|
|
const std::string & | getName () const noexcept |
|
void | initialize (LayeredCostmap *parent, std::string name, tf2_ros::Buffer *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...
|
|
bool | isEnabled () const noexcept |
| getter if the current layer is enabled. More...
|
|
| Layer () |
|
virtual | ~Layer () |
|
|
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) |
|
Definition at line 111 of file inflation_layer.h.
◆ InflationLayer()
costmap_2d::InflationLayer::InflationLayer |
( |
| ) |
|
◆ ~InflationLayer()
virtual costmap_2d::InflationLayer::~InflationLayer |
( |
| ) |
|
|
inlinevirtual |
◆ cellDistance()
unsigned int costmap_2d::InflationLayer::cellDistance |
( |
double |
world_dist | ) |
|
|
inlineprivate |
◆ computeCaches()
void costmap_2d::InflationLayer::computeCaches |
( |
| ) |
|
|
private |
◆ computeCost()
virtual unsigned char costmap_2d::InflationLayer::computeCost |
( |
double |
distance | ) |
const |
|
inlinevirtual |
Given a distance, compute a cost.
- Parameters
-
distance | The distance from an obstacle in cells |
- Returns
- A cost value for the distance
Definition at line 140 of file inflation_layer.h.
◆ costLookup()
unsigned char costmap_2d::InflationLayer::costLookup |
( |
int |
mx, |
|
|
int |
my, |
|
|
int |
src_x, |
|
|
int |
src_y |
|
) |
| |
|
inlineprivate |
Lookup pre-computed costs.
- Parameters
-
mx | The x coordinate of the current cell |
my | The y coordinate of the current cell |
src_x | The x coordinate of the source cell |
src_y | The y coordinate of the source cell |
- Returns
Definition at line 198 of file inflation_layer.h.
◆ deleteKernels()
void costmap_2d::InflationLayer::deleteKernels |
( |
| ) |
|
|
private |
◆ distanceLookup()
double costmap_2d::InflationLayer::distanceLookup |
( |
int |
mx, |
|
|
int |
my, |
|
|
int |
src_x, |
|
|
int |
src_y |
|
) |
| |
|
inlineprivate |
Lookup pre-computed distances.
- Parameters
-
mx | The x coordinate of the current cell |
my | The y coordinate of the current cell |
src_x | The x coordinate of the source cell |
src_y | The y coordinate of the source cell |
- Returns
Definition at line 183 of file inflation_layer.h.
◆ enqueue()
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
-
grid | The costmap |
index | The index of the cell |
mx | The x coordinate of the cell (can be computed from the index, but saves time to store it) |
my | The y coordinate of the cell (can be computed from the index, but saves time to store it) |
src_x | The x index of the obstacle point inflation started at |
src_y | The y index of the obstacle point inflation started at |
Definition at line 291 of file inflation_layer.cpp.
◆ inflate_area()
void costmap_2d::InflationLayer::inflate_area |
( |
int |
min_i, |
|
|
int |
min_j, |
|
|
int |
max_i, |
|
|
int |
max_j, |
|
|
unsigned char * |
master_grid |
|
) |
| |
|
private |
◆ isDiscretized()
virtual bool costmap_2d::InflationLayer::isDiscretized |
( |
| ) |
|
|
inlinevirtual |
◆ matchSize()
void costmap_2d::InflationLayer::matchSize |
( |
| ) |
|
|
virtual |
◆ onFootprintChanged()
void costmap_2d::InflationLayer::onFootprintChanged |
( |
| ) |
|
|
protectedvirtual |
◆ onInitialize()
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 74 of file inflation_layer.cpp.
◆ reconfigureCB()
void costmap_2d::InflationLayer::reconfigureCB |
( |
costmap_2d::InflationPluginConfig & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
private |
◆ reset()
virtual void costmap_2d::InflationLayer::reset |
( |
| ) |
|
|
inlinevirtual |
◆ setInflationParameters()
void costmap_2d::InflationLayer::setInflationParameters |
( |
double |
inflation_radius, |
|
|
double |
cost_scaling_factor |
|
) |
| |
Change the values of the inflation radius parameters.
- Parameters
-
inflation_radius | The new inflation radius |
cost_scaling_factor | The new weight |
Definition at line 369 of file inflation_layer.cpp.
◆ updateBounds()
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 129 of file inflation_layer.cpp.
◆ updateCosts()
void costmap_2d::InflationLayer::updateCosts |
( |
costmap_2d::Costmap2D & |
master_grid, |
|
|
int |
min_i, |
|
|
int |
min_j, |
|
|
int |
max_i, |
|
|
int |
max_j |
|
) |
| |
|
virtual |
◆ cached_cell_inflation_radius_
unsigned int costmap_2d::InflationLayer::cached_cell_inflation_radius_ |
|
private |
◆ cached_costs_
unsigned char** costmap_2d::InflationLayer::cached_costs_ |
|
private |
◆ cached_distances_
double** costmap_2d::InflationLayer::cached_distances_ |
|
private |
◆ cell_inflation_radius_
unsigned int costmap_2d::InflationLayer::cell_inflation_radius_ |
|
private |
◆ dsrv_
dynamic_reconfigure::Server<costmap_2d::InflationPluginConfig>* costmap_2d::InflationLayer::dsrv_ |
|
private |
◆ inflate_unknown_
bool costmap_2d::InflationLayer::inflate_unknown_ |
|
protected |
◆ inflation_access_
boost::recursive_mutex* costmap_2d::InflationLayer::inflation_access_ |
|
protected |
◆ inflation_cells_
std::map<double, std::vector<CellData> > costmap_2d::InflationLayer::inflation_cells_ |
|
private |
◆ inflation_radius_
double costmap_2d::InflationLayer::inflation_radius_ |
|
protected |
◆ inscribed_radius_
double costmap_2d::InflationLayer::inscribed_radius_ |
|
protected |
◆ last_max_x_
double costmap_2d::InflationLayer::last_max_x_ |
|
private |
◆ last_max_y_
double costmap_2d::InflationLayer::last_max_y_ |
|
private |
◆ last_min_x_
double costmap_2d::InflationLayer::last_min_x_ |
|
private |
◆ last_min_y_
double costmap_2d::InflationLayer::last_min_y_ |
|
private |
◆ need_reinflation_
bool costmap_2d::InflationLayer::need_reinflation_ |
|
private |
Indicates that the entire costmap should be reinflated next time around.
Definition at line 231 of file inflation_layer.h.
◆ resolution_
double costmap_2d::InflationLayer::resolution_ |
|
protected |
◆ seen_
bool* costmap_2d::InflationLayer::seen_ |
|
private |
◆ seen_size_
int costmap_2d::InflationLayer::seen_size_ |
|
private |
◆ weight_
double costmap_2d::InflationLayer::weight_ |
|
protected |
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 Mon Mar 6 2023 03:50:17