Go to the documentation of this file.
42 #include <boost/thread.hpp>
43 #include <pluginlib/class_list_macros.hpp>
56 , inflation_radius_(0)
58 , target_cell_value_(0)
59 , dilation_cell_value_ (0)
60 , use_footprint_(true)
61 , inscribed_radius_(0)
63 , inflate_unknown_(false)
64 , cell_inflation_radius_(0)
65 , cached_cell_inflation_radius_(0)
69 , cached_distances_(NULL)
70 , last_min_x_(-
std::numeric_limits<float>::max())
71 , last_min_y_(-
std::numeric_limits<float>::max())
72 , last_max_x_(
std::numeric_limits<float>::max())
73 , last_max_y_(
std::numeric_limits<float>::max())
82 ros::NodeHandle nh(
"~/" +
name_), g_nh;
90 dynamic_reconfigure::Server<costmap_2d::InflationPluginConfig>::CallbackType cb =
91 [
this](
auto& config,
auto level){
reconfigureCB(config, level); };
94 dsrv_->clearCallback();
95 dsrv_->setCallback(cb);
99 dsrv_ =
new dynamic_reconfigure::Server<costmap_2d::InflationPluginConfig>(ros::NodeHandle(
"~/" +
name_));
100 dsrv_->setCallback(cb);
146 double* min_y,
double* max_x,
double* max_y)
189 ROS_DEBUG(
"InflationLayer::onFootprintChanged(): num footprint points: %lu,"
190 " inscribed_radius_ = %.3f, inflation_radius_ = %.3f",
202 ROS_ASSERT_MSG(
inflation_cells_.empty(),
"The inflation list must be empty at the beginning of inflation");
204 unsigned char* master_array = master_grid.
getCharMap();
208 ROS_WARN(
"InflationLayer::updateCosts(): seen_ array is NULL");
214 ROS_WARN(
"InflationLayer::updateCosts(): seen_ array size is wrong");
219 memset(
seen_,
false, size_x * size_y *
sizeof(
bool));
232 max_i =
std::min(
int(size_x), max_i);
233 max_j =
std::min(
int(size_y), max_j);
240 for (
int j = min_j; j < max_j; j++)
242 for (
int i = min_i; i < max_i; i++)
244 int index = master_grid.
getIndex(i, j);
245 unsigned char cost = master_array[index];
258 for (
int i = 0; i < bin->second.
size(); ++i)
261 const CellData& cell = bin->second[i];
263 unsigned int index = cell.
index_;
273 unsigned int mx = cell.
x_;
274 unsigned int my = cell.
y_;
275 unsigned int sx = cell.
src_x_;
276 unsigned int sy = cell.
src_y_;
279 unsigned char cost =
costLookup(mx, my, sx, sy);
280 unsigned char old_cost = master_array[index];
287 master_grid.
setCost(mx, my, cost);
294 enqueue(index - 1, mx - 1, my, sx, sy);
296 enqueue(index - size_x, mx, my - 1, sx, sy);
298 enqueue(index + 1, mx + 1, my, sx, sy);
300 enqueue(index + size_x, mx, my + 1, sx, sy);
317 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 dilation_cell_value_
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.
unsigned char target_cell_value_
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.
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
Set the cost of a cell in the costmap.
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.
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.