inflation_layer.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2008, 2013, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of Willow Garage, Inc. nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  * Author: Eitan Marder-Eppstein
00036  *         David V. Lu!!
00037  *********************************************************************/
00038 #include <costmap_2d/inflation_layer.h>
00039 #include <costmap_2d/costmap_math.h>
00040 #include <costmap_2d/footprint.h>
00041 #include <pluginlib/class_list_macros.h>
00042 
00043 PLUGINLIB_EXPORT_CLASS(costmap_2d::InflationLayer, costmap_2d::Layer)
00044 
00045 using costmap_2d::LETHAL_OBSTACLE;
00046 using costmap_2d::INSCRIBED_INFLATED_OBSTACLE;
00047 using costmap_2d::NO_INFORMATION;
00048 
00049 namespace costmap_2d
00050 {
00051 
00052 InflationLayer::InflationLayer()
00053   : inflation_radius_( 0 )
00054   , weight_( 0 )
00055   , cell_inflation_radius_(0)
00056   , cached_cell_inflation_radius_(0)
00057   , dsrv_(NULL)
00058 {
00059   access_ = new boost::shared_mutex();
00060 }
00061 
00062 void InflationLayer::onInitialize()
00063 {
00064   {
00065     boost::unique_lock < boost::shared_mutex > lock(*access_);
00066     ros::NodeHandle nh("~/" + name_), g_nh;
00067     current_ = true;
00068     seen_ = NULL;
00069     need_reinflation_ = false;
00070 
00071     dynamic_reconfigure::Server<costmap_2d::InflationPluginConfig>::CallbackType cb = boost::bind(
00072         &InflationLayer::reconfigureCB, this, _1, _2);
00073 
00074     if(dsrv_ != NULL){
00075       dsrv_->clearCallback();
00076       dsrv_->setCallback(cb);
00077     }
00078     else
00079     {
00080       dsrv_ = new dynamic_reconfigure::Server<costmap_2d::InflationPluginConfig>(ros::NodeHandle("~/" + name_));
00081       dsrv_->setCallback(cb);
00082     }
00083 
00084   }
00085 
00086   matchSize();
00087 }
00088 
00089 void InflationLayer::reconfigureCB(costmap_2d::InflationPluginConfig &config, uint32_t level)
00090 {
00091   if (weight_ != config.cost_scaling_factor || inflation_radius_ != config.inflation_radius)
00092   {
00093     inflation_radius_ = config.inflation_radius;
00094     cell_inflation_radius_ = cellDistance(inflation_radius_);
00095     weight_ = config.cost_scaling_factor;
00096     need_reinflation_ = true;
00097     computeCaches();
00098   }
00099 
00100   if (enabled_ != config.enabled) {
00101     enabled_ = config.enabled;
00102     need_reinflation_ = true;
00103   }
00104 }
00105 
00106 void InflationLayer::matchSize()
00107 {
00108   boost::unique_lock < boost::shared_mutex > lock(*access_);
00109   costmap_2d::Costmap2D* costmap = layered_costmap_->getCostmap();
00110   resolution_ = costmap->getResolution();
00111   cell_inflation_radius_ = cellDistance(inflation_radius_);
00112   computeCaches();
00113 
00114   unsigned int size_x = costmap->getSizeInCellsX(), size_y = costmap->getSizeInCellsY();
00115   if (seen_)
00116     delete seen_;
00117   seen_ = new bool[size_x * size_y];
00118 }
00119 
00120 void InflationLayer::updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x,
00121                                            double* min_y, double* max_x, double* max_y)
00122 {
00123   if( need_reinflation_ )
00124   {
00125     // For some reason when I make these -<double>::max() it does not
00126     // work with Costmap2D::worldToMapEnforceBounds(), so I'm using
00127     // -<float>::max() instead.
00128     *min_x = -std::numeric_limits<float>::max();
00129     *min_y = -std::numeric_limits<float>::max();
00130     *max_x = std::numeric_limits<float>::max();
00131     *max_y = std::numeric_limits<float>::max();
00132     need_reinflation_ = false;
00133   }
00134 }
00135 
00136 void InflationLayer::onFootprintChanged()
00137 {
00138   inscribed_radius_ = layered_costmap_->getInscribedRadius();
00139   cell_inflation_radius_ = cellDistance( inflation_radius_ );
00140   computeCaches();
00141   need_reinflation_ = true;
00142 
00143   ROS_DEBUG( "InflationLayer::onFootprintChanged(): num footprint points: %lu, inscribed_radius_ = %.3f, inflation_radius_ = %.3f",
00144              layered_costmap_->getFootprint().size(), inscribed_radius_, inflation_radius_ );
00145 }
00146 
00147 void InflationLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i,
00148                                           int max_j)
00149 {
00150   boost::unique_lock < boost::shared_mutex > lock(*access_);
00151   if (!enabled_)
00152     return;
00153 
00154   //make sure the inflation queue is empty at the beginning of the cycle (should always be true)
00155   ROS_ASSERT_MSG(inflation_queue_.empty(), "The inflation queue must be empty at the beginning of inflation");
00156 
00157   unsigned char* master_array = master_grid.getCharMap();
00158   unsigned int size_x = master_grid.getSizeInCellsX(), size_y = master_grid.getSizeInCellsY();
00159 
00160   memset(seen_, false, size_x * size_y * sizeof(bool));
00161 
00162   // We need to include in the inflation cells outside the bounding
00163   // box min_i...max_j, by the amount cell_inflation_radius_.  Cells
00164   // up to that distance outside the box can still influence the costs
00165   // stored in cells inside the box.
00166   min_i -= cell_inflation_radius_;
00167   min_j -= cell_inflation_radius_;
00168   max_i += cell_inflation_radius_;
00169   max_j += cell_inflation_radius_;
00170 
00171   min_i = std::max( 0, min_i );
00172   min_j = std::max( 0, min_j );
00173   max_i = std::min( int( size_x  ), max_i );
00174   max_j = std::min( int( size_y  ), max_j );
00175 
00176   for (int j = min_j; j < max_j; j++)
00177   {
00178     for (int i = min_i; i < max_i; i++)
00179     {
00180       int index = master_grid.getIndex(i, j);
00181       unsigned char cost = master_array[index];
00182       if (cost == LETHAL_OBSTACLE)
00183       {
00184         enqueue(master_array, index, i, j, i, j);
00185       }
00186     }
00187   }
00188 
00189   while (!inflation_queue_.empty())
00190   {
00191     //get the highest priority cell and pop it off the priority queue
00192     const CellData& current_cell = inflation_queue_.top();
00193 
00194     unsigned int index = current_cell.index_;
00195     unsigned int mx = current_cell.x_;
00196     unsigned int my = current_cell.y_;
00197     unsigned int sx = current_cell.src_x_;
00198     unsigned int sy = current_cell.src_y_;
00199 
00200     //pop once we have our cell info
00201     inflation_queue_.pop();
00202 
00203     //attempt to put the neighbors of the current cell onto the queue
00204     if (mx > 0)
00205       enqueue(master_array, index - 1, mx - 1, my, sx, sy);
00206     if (my > 0)
00207       enqueue(master_array, index - size_x, mx, my - 1, sx, sy);
00208     if (mx < size_x - 1)
00209       enqueue(master_array, index + 1, mx + 1, my, sx, sy);
00210     if (my < size_y - 1)
00211       enqueue(master_array, index + size_x, mx, my + 1, sx, sy);
00212   }
00213 }
00214 
00224 inline void InflationLayer::enqueue(unsigned char* grid, unsigned int index, unsigned int mx, unsigned int my,
00225                                             unsigned int src_x, unsigned int src_y)
00226 {
00227 
00228   //set the cost of the cell being inserted
00229   if (!seen_[index])
00230   {
00231     //we compute our distance table one cell further than the inflation radius dictates so we can make the check below
00232     double distance = distanceLookup(mx, my, src_x, src_y);
00233 
00234     //we only want to put the cell in the queue if it is within the inflation radius of the obstacle point
00235     if (distance > cell_inflation_radius_)
00236       return;
00237 
00238     //assign the cost associated with the distance from an obstacle to the cell
00239     unsigned char cost = costLookup(mx, my, src_x, src_y);
00240     unsigned char old_cost = grid[index];
00241 
00242     if (old_cost == NO_INFORMATION && cost >= INSCRIBED_INFLATED_OBSTACLE)
00243       grid[index] = cost;
00244     else
00245       grid[index] = std::max(old_cost, cost);
00246     //push the cell data onto the queue and mark
00247     seen_[index] = true;
00248     CellData data(distance, index, mx, my, src_x, src_y);
00249     inflation_queue_.push(data);
00250   }
00251 }
00252 
00253 void InflationLayer::computeCaches()
00254 {
00255   if(cell_inflation_radius_ == 0)
00256     return;
00257 
00258   //based on the inflation radius... compute distance and cost caches
00259   if(cell_inflation_radius_ != cached_cell_inflation_radius_)
00260   {
00261     if(cached_cell_inflation_radius_ > 0)
00262       deleteKernels();
00263 
00264     cached_costs_ = new unsigned char*[cell_inflation_radius_ + 2];
00265     cached_distances_ = new double*[cell_inflation_radius_ + 2];
00266 
00267     for (unsigned int i = 0; i <= cell_inflation_radius_ + 1; ++i)
00268     {
00269       cached_costs_[i] = new unsigned char[cell_inflation_radius_ + 2];
00270       cached_distances_[i] = new double[cell_inflation_radius_ + 2];
00271       for (unsigned int j = 0; j <= cell_inflation_radius_ + 1; ++j)
00272       {
00273         cached_distances_[i][j] = hypot(i, j);
00274       }
00275     }
00276 
00277     cached_cell_inflation_radius_ = cell_inflation_radius_;
00278   }
00279 
00280   for (unsigned int i = 0; i <= cell_inflation_radius_ + 1; ++i)
00281   {
00282     for (unsigned int j = 0; j <= cell_inflation_radius_ + 1; ++j)
00283     {
00284       cached_costs_[i][j] = computeCost(cached_distances_[i][j]);
00285     }
00286   }
00287 }
00288 
00289 void InflationLayer::deleteKernels()
00290 {
00291   if (cached_distances_ != NULL)
00292   {
00293     for (unsigned int i = 0; i <= cached_cell_inflation_radius_ + 1; ++i)
00294     {
00295       delete[] cached_distances_[i];
00296     }
00297     delete[] cached_distances_;
00298   }
00299 
00300   if (cached_costs_ != NULL)
00301   {
00302     for (unsigned int i = 0; i <= cached_cell_inflation_radius_ + 1; ++i)
00303     {
00304       delete[] cached_costs_[i];
00305     }
00306     delete[] cached_costs_;
00307   }
00308 }
00309 
00310 }  // namespace costmap_2d


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