Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 #include <costmap_model.h>
00038 
00039 using namespace std;
00040 using namespace costmap_2d;
00041 
00042 namespace iri_ackermann_local_planner {
00043   CostmapModel::CostmapModel(const Costmap2D& ma) : costmap_(ma) {}
00044 
00045   double CostmapModel::footprintCost(const geometry_msgs::Point& position, const vector<geometry_msgs::Point>& footprint, 
00046       double inscribed_radius, double circumscribed_radius){
00047     
00048     unsigned int cell_x, cell_y;
00049 
00050     
00051     if(!costmap_.worldToMap(position.x, position.y, cell_x, cell_y))
00052       return -1.0;
00053 
00054     
00055     if(footprint.size() < 3){
00056       unsigned char cost = costmap_.getCost(cell_x, cell_y);
00057       
00058       if(cost == LETHAL_OBSTACLE || cost == INSCRIBED_INFLATED_OBSTACLE || cost == NO_INFORMATION)
00059         return -1.0;
00060       return cost;
00061     }
00062 
00063     
00064     unsigned int x0, x1, y0, y1;
00065     double line_cost = 0.0;
00066     double footprint_cost = 0.0;
00067 
00068     
00069     for(unsigned int i = 0; i < footprint.size() - 1; ++i){
00070       
00071       if(!costmap_.worldToMap(footprint[i].x, footprint[i].y, x0, y0))
00072         return -1.0;
00073 
00074       
00075       if(!costmap_.worldToMap(footprint[i + 1].x, footprint[i + 1].y, x1, y1))
00076         return -1.0;
00077 
00078       line_cost = lineCost(x0, x1, y0, y1);
00079       footprint_cost = std::max(line_cost, footprint_cost);
00080 
00081       
00082       if(line_cost < 0)
00083         return -1.0;
00084     }
00085 
00086     
00087     
00088     if(!costmap_.worldToMap(footprint.back().x, footprint.back().y, x0, y0))
00089       return -1.0;
00090 
00091     
00092     if(!costmap_.worldToMap(footprint.front().x, footprint.front().y, x1, y1))
00093       return -1.0;
00094 
00095     line_cost = lineCost(x0, x1, y0, y1);
00096     footprint_cost = std::max(line_cost, footprint_cost);
00097 
00098     if(line_cost < 0)
00099       return -1.0;
00100 
00101     
00102     return footprint_cost;
00103 
00104   }
00105 
00106   
00107   double CostmapModel::lineCost(int x0, int x1, 
00108       int y0, int y1){
00109     
00110     int deltax = abs(x1 - x0);        
00111     int deltay = abs(y1 - y0);        
00112     int x = x0;                       
00113     int y = y0;                       
00114 
00115     int xinc1, xinc2, yinc1, yinc2;
00116     int den, num, numadd, numpixels;
00117 
00118     double line_cost = 0.0;
00119     double point_cost = -1.0;
00120 
00121     if (x1 >= x0)                 
00122     {
00123       xinc1 = 1;
00124       xinc2 = 1;
00125     }
00126     else                          
00127     {
00128       xinc1 = -1;
00129       xinc2 = -1;
00130     }
00131 
00132     if (y1 >= y0)                 
00133     {
00134       yinc1 = 1;
00135       yinc2 = 1;
00136     }
00137     else                          
00138     {
00139       yinc1 = -1;
00140       yinc2 = -1;
00141     }
00142 
00143     if (deltax >= deltay)         
00144     {
00145       xinc1 = 0;                  
00146       yinc2 = 0;                  
00147       den = deltax;
00148       num = deltax / 2;
00149       numadd = deltay;
00150       numpixels = deltax;         
00151     }
00152     else                          
00153     {
00154       xinc2 = 0;                  
00155       yinc1 = 0;                  
00156       den = deltay;
00157       num = deltay / 2;
00158       numadd = deltax;
00159       numpixels = deltay;         
00160     }
00161 
00162     for (int curpixel = 0; curpixel <= numpixels; curpixel++)
00163     {
00164       point_cost = pointCost(x, y); 
00165 
00166       if(point_cost < 0)
00167         return -1;
00168 
00169       if(line_cost < point_cost)
00170         line_cost = point_cost;
00171 
00172       num += numadd;              
00173       if (num >= den)             
00174       {
00175         num -= den;               
00176         x += xinc1;               
00177         y += yinc1;               
00178       }
00179       x += xinc2;                 
00180       y += yinc2;                 
00181     }
00182 
00183     return line_cost;
00184   }
00185 
00186   double CostmapModel::pointCost(int x, int y){
00187     unsigned char cost = costmap_.getCost(x, y);
00188     
00189     
00190     if(cost == LETHAL_OBSTACLE || cost == NO_INFORMATION){
00191       return -1;
00192     }
00193 
00194     return cost;
00195   }
00196 
00197 };