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 <base_local_planner/line_iterator.h>
00038 #include <base_local_planner/costmap_model.h>
00039 #include <costmap_2d/cost_values.h>
00040
00041 using namespace std;
00042 using namespace costmap_2d;
00043
00044 namespace base_local_planner {
00045 CostmapModel::CostmapModel(const Costmap2D& ma) : costmap_(ma) {}
00046
00047 double CostmapModel::footprintCost(const geometry_msgs::Point& position, const std::vector<geometry_msgs::Point>& footprint,
00048 double inscribed_radius, double circumscribed_radius){
00049
00050
00051 unsigned int cell_x, cell_y;
00052
00053
00054 if(!costmap_.worldToMap(position.x, position.y, cell_x, cell_y))
00055 return -1.0;
00056
00057
00058 if(footprint.size() < 3){
00059 unsigned char cost = costmap_.getCost(cell_x, cell_y);
00060
00061 if(cost == LETHAL_OBSTACLE || cost == INSCRIBED_INFLATED_OBSTACLE || cost == NO_INFORMATION)
00062 return -1.0;
00063 return cost;
00064 }
00065
00066
00067 unsigned int x0, x1, y0, y1;
00068 double line_cost = 0.0;
00069 double footprint_cost = 0.0;
00070
00071
00072 for(unsigned int i = 0; i < footprint.size() - 1; ++i){
00073
00074 if(!costmap_.worldToMap(footprint[i].x, footprint[i].y, x0, y0))
00075 return -1.0;
00076
00077
00078 if(!costmap_.worldToMap(footprint[i + 1].x, footprint[i + 1].y, x1, y1))
00079 return -1.0;
00080
00081 line_cost = lineCost(x0, x1, y0, y1);
00082 footprint_cost = std::max(line_cost, footprint_cost);
00083
00084
00085 if(line_cost < 0)
00086 return -1.0;
00087 }
00088
00089
00090
00091 if(!costmap_.worldToMap(footprint.back().x, footprint.back().y, x0, y0))
00092 return -1.0;
00093
00094
00095 if(!costmap_.worldToMap(footprint.front().x, footprint.front().y, x1, y1))
00096 return -1.0;
00097
00098 line_cost = lineCost(x0, x1, y0, y1);
00099 footprint_cost = std::max(line_cost, footprint_cost);
00100
00101 if(line_cost < 0)
00102 return -1.0;
00103
00104
00105 return footprint_cost;
00106
00107 }
00108
00109
00110 double CostmapModel::lineCost(int x0, int x1,
00111 int y0, int y1){
00112
00113 double line_cost = 0.0;
00114 double point_cost = -1.0;
00115
00116 for( LineIterator line( x0, y0, x1, y1 ); line.isValid(); line.advance() )
00117 {
00118 point_cost = pointCost( line.getX(), line.getY() );
00119
00120 if(point_cost < 0)
00121 return -1;
00122
00123 if(line_cost < point_cost)
00124 line_cost = point_cost;
00125 }
00126
00127 return line_cost;
00128 }
00129
00130 double CostmapModel::pointCost(int x, int y){
00131 unsigned char cost = costmap_.getCost(x, y);
00132
00133
00134 if(cost == LETHAL_OBSTACLE || cost == NO_INFORMATION){
00135 return -1;
00136 }
00137
00138 return cost;
00139 }
00140
00141 };