Go to the documentation of this file.
38 #ifndef COSTMAP_2D_INFLATION_LAYER_H_
39 #define COSTMAP_2D_INFLATION_LAYER_H_
44 #include <costmap_2d/InflationPluginConfig.h>
45 #include <dynamic_reconfigure/server.h>
46 #include <boost/thread.hpp>
66 CellData(
double i,
unsigned int x,
unsigned int y,
unsigned int sx,
unsigned int sy) :
75 class InflationLayer :
public Layer
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);
106 unsigned char cost = 0;
147 inline double distanceLookup(
int mx,
int my,
int src_x,
int src_y)
149 unsigned int dx = abs(mx - src_x);
150 unsigned int dy = abs(my - src_y);
162 inline unsigned char costLookup(
int mx,
int my,
int src_x,
int src_y)
164 unsigned int dx = abs(mx - src_x);
165 unsigned int dy = abs(my - src_y);
171 void inflate_area(
int min_i,
int min_j,
int max_i,
int max_j,
unsigned char* master_grid);
178 inline void enqueue(
unsigned int index,
unsigned int mx,
unsigned int my,
179 unsigned int src_x,
unsigned int src_y);
192 dynamic_reconfigure::Server<costmap_2d::InflationPluginConfig> *
dsrv_;
193 void reconfigureCB(costmap_2d::InflationPluginConfig &config, uint32_t level);
200 #endif // COSTMAP_2D_INFLATION_LAYER_H_
boost::recursive_mutex * inflation_access_
std::map< double, std::vector< CellData > > inflation_cells_
virtual bool isDiscretized()
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_
void inflate_area(int min_i, int min_j, int max_i, int max_j, unsigned char *master_grid)
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 ~InflationLayer()
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization.
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 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".
LayeredCostmap * layered_costmap_
double ** cached_distances_
bool need_reinflation_
Indicates that the entire costmap should be reinflated next time around.
CellData(double i, unsigned int x, unsigned int y, unsigned int sx, unsigned int sy)
Constructor for a CellData objects.
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.
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_
unsigned int cellDistance(double world_dist)
Given distance in the world... convert it to cells.
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...
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