costmap_2d.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/costmap_2d.h>
00039 #include <cstdio>
00040 
00041 using namespace std;
00042 
00043 namespace costmap_2d
00044 {
00045 Costmap2D::Costmap2D(unsigned int cells_size_x, unsigned int cells_size_y, double resolution,
00046                      double origin_x, double origin_y, unsigned char default_value) :
00047     size_x_(cells_size_x), size_y_(cells_size_y), resolution_(resolution), origin_x_(origin_x), 
00048     origin_y_(origin_y), costmap_(NULL), default_value_(default_value)
00049 {
00050   access_ = new boost::shared_mutex();
00051 
00052   //create the costmap
00053   initMaps(size_x_, size_y_);
00054   resetMaps();
00055 }
00056 
00057 void Costmap2D::deleteMaps()
00058 {
00059   //clean up data
00060   boost::unique_lock < boost::shared_mutex > lock(*access_);
00061   delete[] costmap_;
00062   costmap_ = NULL;
00063 }
00064 
00065 void Costmap2D::initMaps(unsigned int size_x, unsigned int size_y)
00066 {
00067   boost::unique_lock < boost::shared_mutex > lock(*access_);
00068   delete[] costmap_;
00069   costmap_ = new unsigned char[size_x * size_y];
00070 }
00071 
00072 void Costmap2D::resizeMap(unsigned int size_x, unsigned int size_y, double resolution,
00073                           double origin_x, double origin_y)
00074 {
00075   size_x_ = size_x;
00076   size_y_ = size_y;
00077   resolution_ = resolution;
00078   origin_x_ = origin_x;
00079   origin_y_ = origin_y;
00080 
00081   initMaps(size_x, size_y);
00082 
00083   // reset our maps to have no information
00084   resetMaps();
00085 }
00086 
00087 void Costmap2D::resetMaps()
00088 {
00089   boost::unique_lock < boost::shared_mutex > lock(*access_);
00090   memset(costmap_, default_value_, size_x_ * size_y_ * sizeof(unsigned char));
00091 }
00092 
00093 void Costmap2D::resetMap(unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
00094 {
00095   boost::unique_lock < boost::shared_mutex > lock(*(access_));
00096   unsigned int len = xn - x0;
00097   for (unsigned int y = y0 * size_x_ + x0; y < yn * size_x_ + x0; y += size_x_)
00098     memset(costmap_ + y, default_value_, len * sizeof(unsigned char));
00099 }
00100 
00101 bool Costmap2D::copyCostmapWindow(const Costmap2D& map, double win_origin_x, double win_origin_y, double win_size_x,
00102                                   double win_size_y)
00103 {
00104   //check for self windowing
00105   if (this == &map)
00106   {
00107     // ROS_ERROR("Cannot convert this costmap into a window of itself");
00108     return false;
00109   }
00110 
00111   //clean up old data
00112   deleteMaps();
00113 
00114   //compute the bounds of our new map
00115   unsigned int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
00116   if (!map.worldToMap(win_origin_x, win_origin_y, lower_left_x, lower_left_y)
00117       || !map.worldToMap(win_origin_x + win_size_x, win_origin_y + win_size_y, upper_right_x, upper_right_y))
00118   {
00119     // ROS_ERROR("Cannot window a map that the window bounds don't fit inside of");
00120     return false;
00121   }
00122 
00123   size_x_ = upper_right_x - lower_left_x;
00124   size_y_ = upper_right_y - lower_left_y;
00125   resolution_ = map.resolution_;
00126   origin_x_ = win_origin_x;
00127   origin_y_ = win_origin_y;
00128 
00129   //initialize our various maps and reset markers for inflation
00130   initMaps(size_x_, size_y_);
00131 
00132   //copy the window of the static map and the costmap that we're taking
00133   copyMapRegion(map.costmap_, lower_left_x, lower_left_y, map.size_x_, costmap_, 0, 0, size_x_, size_x_, size_y_);
00134   return true;
00135 }
00136 
00137 Costmap2D& Costmap2D::operator=(const Costmap2D& map)
00138 {
00139 
00140   //check for self assignement
00141   if (this == &map)
00142     return *this;
00143 
00144   //clean up old data
00145   deleteMaps();
00146 
00147   size_x_ = map.size_x_;
00148   size_y_ = map.size_y_;
00149   resolution_ = map.resolution_;
00150   origin_x_ = map.origin_x_;
00151   origin_y_ = map.origin_y_;
00152 
00153   //initialize our various maps
00154   initMaps(size_x_, size_y_);
00155 
00156   //copy the cost map
00157   memcpy(costmap_, map.costmap_, size_x_ * size_y_ * sizeof(unsigned char));
00158 
00159   return *this;
00160 }
00161 
00162 Costmap2D::Costmap2D(const Costmap2D& map) :
00163     costmap_(NULL)
00164 {
00165   *this = map;
00166 }
00167 
00168 //just initialize everything to NULL by default
00169 Costmap2D::Costmap2D() :
00170     size_x_(0), size_y_(0), resolution_(0.0), origin_x_(0.0), origin_y_(0.0), costmap_(NULL)
00171 {
00172   access_ = new boost::shared_mutex();
00173 }
00174 
00175 Costmap2D::~Costmap2D()
00176 {
00177   deleteMaps();
00178 }
00179 
00180 unsigned int Costmap2D::cellDistance(double world_dist)
00181 {
00182   double cells_dist = max(0.0, ceil(world_dist / resolution_));
00183   return (unsigned int)cells_dist;
00184 }
00185 
00186 unsigned char* Costmap2D::getCharMap() const
00187 {
00188   return costmap_;
00189 }
00190 
00191 unsigned char Costmap2D::getCost(unsigned int mx, unsigned int my) const
00192 {
00193   return costmap_[getIndex(mx, my)];
00194 }
00195 
00196 void Costmap2D::setCost(unsigned int mx, unsigned int my, unsigned char cost)
00197 {
00198   costmap_[getIndex(mx, my)] = cost;
00199 }
00200 
00201 void Costmap2D::mapToWorld(unsigned int mx, unsigned int my, double& wx, double& wy) const
00202 {
00203   wx = origin_x_ + (mx + 0.5) * resolution_;
00204   wy = origin_y_ + (my + 0.5) * resolution_;
00205 }
00206 
00207 bool Costmap2D::worldToMap(double wx, double wy, unsigned int& mx, unsigned int& my) const
00208 {
00209   if (wx < origin_x_ || wy < origin_y_)
00210     return false;
00211 
00212   mx = (int)((wx - origin_x_) / resolution_);
00213   my = (int)((wy - origin_y_) / resolution_);
00214 
00215   if (mx < size_x_ && my < size_y_)
00216     return true;
00217 
00218   return false;
00219 }
00220 
00221 void Costmap2D::worldToMapNoBounds(double wx, double wy, int& mx, int& my) const
00222 {
00223   mx = (int)((wx - origin_x_) / resolution_);
00224   my = (int)((wy - origin_y_) / resolution_);
00225 }
00226 
00227 void Costmap2D::worldToMapEnforceBounds(double wx, double wy, int& mx, int& my) const
00228 {
00229   // Here we avoid doing any math to wx,wy before comparing them to
00230   // the bounds, so their values can go out to the max and min values
00231   // of double floating point.
00232   if( wx < origin_x_ )
00233   {
00234     mx = 0;
00235   }
00236   else if( wx > resolution_ * size_x_ + origin_x_ )
00237   {
00238     mx = size_x_ - 1;
00239   }
00240   else
00241   {
00242     mx = (int)((wx - origin_x_) / resolution_);
00243   }
00244 
00245   if( wy < origin_y_ )
00246   {
00247     my = 0;
00248   }
00249   else if( wy > resolution_ * size_y_ + origin_y_ )
00250   {
00251     my = size_y_ - 1;
00252   }
00253   else
00254   {
00255     my = (int)((wy - origin_y_) / resolution_);
00256   }
00257 }
00258 
00259 void Costmap2D::updateOrigin(double new_origin_x, double new_origin_y)
00260 {
00261   //project the new origin into the grid
00262   int cell_ox, cell_oy;
00263   cell_ox = int((new_origin_x - origin_x_) / resolution_);
00264   cell_oy = int((new_origin_y - origin_y_) / resolution_);
00265 
00266   //compute the associated world coordinates for the origin cell
00267   //because we want to keep things grid-aligned
00268   double new_grid_ox, new_grid_oy;
00269   new_grid_ox = origin_x_ + cell_ox * resolution_;
00270   new_grid_oy = origin_y_ + cell_oy * resolution_;
00271 
00272   //To save casting from unsigned int to int a bunch of times
00273   int size_x = size_x_;
00274   int size_y = size_y_;
00275 
00276   //we need to compute the overlap of the new and existing windows
00277   int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
00278   lower_left_x = min(max(cell_ox, 0), size_x);
00279   lower_left_y = min(max(cell_oy, 0), size_y);
00280   upper_right_x = min(max(cell_ox + size_x, 0), size_x);
00281   upper_right_y = min(max(cell_oy + size_y, 0), size_y);
00282 
00283   unsigned int cell_size_x = upper_right_x - lower_left_x;
00284   unsigned int cell_size_y = upper_right_y - lower_left_y;
00285 
00286   //we need a map to store the obstacles in the window temporarily
00287   unsigned char* local_map = new unsigned char[cell_size_x * cell_size_y];
00288 
00289   //copy the local window in the costmap to the local map
00290   copyMapRegion(costmap_, lower_left_x, lower_left_y, size_x_, local_map, 0, 0, cell_size_x, cell_size_x, cell_size_y);
00291 
00292   //now we'll set the costmap to be completely unknown if we track unknown space
00293   resetMaps();
00294 
00295   //update the origin with the appropriate world coordinates
00296   origin_x_ = new_grid_ox;
00297   origin_y_ = new_grid_oy;
00298 
00299   //compute the starting cell location for copying data back in
00300   int start_x = lower_left_x - cell_ox;
00301   int start_y = lower_left_y - cell_oy;
00302 
00303   //now we want to copy the overlapping information back into the map, but in its new location
00304   copyMapRegion(local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x, cell_size_y);
00305 
00306   //make sure to clean up
00307   delete[] local_map;
00308 }
00309 
00310 bool Costmap2D::setConvexPolygonCost(const std::vector<geometry_msgs::Point>& polygon, unsigned char cost_value)
00311 {
00312   //we assume the polygon is given in the global_frame... we need to transform it to map coordinates
00313   std::vector<MapLocation> map_polygon;
00314   for (unsigned int i = 0; i < polygon.size(); ++i)
00315   {
00316     MapLocation loc;
00317     if (!worldToMap(polygon[i].x, polygon[i].y, loc.x, loc.y))
00318     {
00319       // ("Polygon lies outside map bounds, so we can't fill it");
00320       return false;
00321     }
00322     map_polygon.push_back(loc);
00323   }
00324 
00325   std::vector<MapLocation> polygon_cells;
00326 
00327   //get the cells that fill the polygon
00328   convexFillCells(map_polygon, polygon_cells);
00329 
00330   //set the cost of those cells
00331   for (unsigned int i = 0; i < polygon_cells.size(); ++i)
00332   {
00333     unsigned int index = getIndex(polygon_cells[i].x, polygon_cells[i].y);
00334     costmap_[index] = cost_value;
00335   }
00336   return true;
00337 }
00338 
00339 void Costmap2D::polygonOutlineCells(const std::vector<MapLocation>& polygon, std::vector<MapLocation>& polygon_cells)
00340 {
00341   PolygonOutlineCells cell_gatherer(*this, costmap_, polygon_cells);
00342   for (unsigned int i = 0; i < polygon.size() - 1; ++i)
00343   {
00344     raytraceLine(cell_gatherer, polygon[i].x, polygon[i].y, polygon[i + 1].x, polygon[i + 1].y);
00345   }
00346   if (!polygon.empty())
00347   {
00348     unsigned int last_index = polygon.size() - 1;
00349     //we also need to close the polygon by going from the last point to the first
00350     raytraceLine(cell_gatherer, polygon[last_index].x, polygon[last_index].y, polygon[0].x, polygon[0].y);
00351   }
00352 }
00353 
00354 void Costmap2D::convexFillCells(const std::vector<MapLocation>& polygon, std::vector<MapLocation>& polygon_cells)
00355 {
00356   //we need a minimum polygon of a triangle
00357   if (polygon.size() < 3)
00358     return;
00359 
00360   //first get the cells that make up the outline of the polygon
00361   polygonOutlineCells(polygon, polygon_cells);
00362 
00363   //quick bubble sort to sort points by x
00364   MapLocation swap;
00365   unsigned int i = 0;
00366   while (i < polygon_cells.size() - 1)
00367   {
00368     if (polygon_cells[i].x > polygon_cells[i + 1].x)
00369     {
00370       swap = polygon_cells[i];
00371       polygon_cells[i] = polygon_cells[i + 1];
00372       polygon_cells[i + 1] = swap;
00373 
00374       if (i > 0)
00375         --i;
00376     }
00377     else
00378       ++i;
00379   }
00380 
00381   i = 0;
00382   MapLocation min_pt;
00383   MapLocation max_pt;
00384   unsigned int min_x = polygon_cells[0].x;
00385   unsigned int max_x = polygon_cells[polygon_cells.size() - 1].x;
00386 
00387   //walk through each column and mark cells inside the polygon
00388   for (unsigned int x = min_x; x <= max_x; ++x)
00389   {
00390     if (i >= polygon_cells.size() - 1)
00391       break;
00392 
00393     if (polygon_cells[i].y < polygon_cells[i + 1].y)
00394     {
00395       min_pt = polygon_cells[i];
00396       max_pt = polygon_cells[i + 1];
00397     }
00398     else
00399     {
00400       min_pt = polygon_cells[i + 1];
00401       max_pt = polygon_cells[i];
00402     }
00403 
00404     i += 2;
00405     while (i < polygon_cells.size() && polygon_cells[i].x == x)
00406     {
00407       if (polygon_cells[i].y < min_pt.y)
00408         min_pt = polygon_cells[i];
00409       else if (polygon_cells[i].y > max_pt.y)
00410         max_pt = polygon_cells[i];
00411       ++i;
00412     }
00413 
00414     MapLocation pt;
00415     //loop though cells in the column
00416     for (unsigned int y = min_pt.y; y < max_pt.y; ++y)
00417     {
00418       pt.x = x;
00419       pt.y = y;
00420       polygon_cells.push_back(pt);
00421 
00422     }
00423   }
00424 }
00425 
00426 unsigned int Costmap2D::getSizeInCellsX() const
00427 {
00428   return size_x_;
00429 }
00430 
00431 unsigned int Costmap2D::getSizeInCellsY() const
00432 {
00433   return size_y_;
00434 }
00435 
00436 double Costmap2D::getSizeInMetersX() const
00437 {
00438   return (size_x_ - 1 + 0.5) * resolution_;
00439 }
00440 
00441 double Costmap2D::getSizeInMetersY() const
00442 {
00443   return (size_y_ - 1 + 0.5) * resolution_;
00444 }
00445 
00446 double Costmap2D::getOriginX() const
00447 {
00448   return origin_x_;
00449 }
00450 
00451 double Costmap2D::getOriginY() const
00452 {
00453   return origin_y_;
00454 }
00455 
00456 double Costmap2D::getResolution() const
00457 {
00458   return resolution_;
00459 }
00460 
00461 bool Costmap2D::saveMap(std::string file_name)
00462 {
00463   FILE *fp = fopen(file_name.c_str(), "w");
00464 
00465   if (!fp)
00466   {
00467     return false;
00468   }
00469 
00470   fprintf(fp, "P2\n%u\n%u\n%u\n", size_x_, size_y_, 0xff);
00471   for (unsigned int iy = 0; iy < size_y_; iy++)
00472   {
00473     for (unsigned int ix = 0; ix < size_x_; ix++)
00474     {
00475       unsigned char cost = getCost(ix, iy);
00476       fprintf(fp, "%d ", cost);
00477     }
00478     fprintf(fp, "\n");
00479   }
00480   fclose(fp);
00481   return true;
00482 }
00483 
00484 }


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