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