45 CostmapModel::CostmapModel(
const Costmap2D& ma) : costmap_(ma) {}
48 double inscribed_radius,
double circumscribed_radius){
51 unsigned int cell_x, cell_y;
58 if(footprint.size() < 3){
61 if(cost == LETHAL_OBSTACLE || cost == INSCRIBED_INFLATED_OBSTACLE || cost == NO_INFORMATION)
67 unsigned int x0, x1, y0, y1;
68 double line_cost = 0.0;
69 double footprint_cost = 0.0;
72 for(
unsigned int i = 0; i < footprint.size() - 1; ++i){
81 line_cost =
lineCost(x0, x1, y0, y1);
82 footprint_cost = std::max(line_cost, footprint_cost);
98 line_cost =
lineCost(x0, x1, y0, y1);
99 footprint_cost = std::max(line_cost, footprint_cost);
105 return footprint_cost;
111 double line_cost = 0.0;
112 double point_cost = -1.0;
116 point_cost =
pointCost( line.getX(), line.getY() );
121 if(line_cost < point_cost)
122 line_cost = point_cost;
132 if(cost == LETHAL_OBSTACLE || cost == NO_INFORMATION){
const costmap_2d::Costmap2D & costmap_
Allows access of costmap obstacle information.
double pointCost(int x, int y) const
Checks the cost of a point in the costmap.
unsigned char getCost(unsigned int mx, unsigned int my) const
double lineCost(int x0, int x1, int y0, int y1) const
Rasterizes a line in the costmap grid and checks for collisions.
virtual double footprintCost(const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius)
Checks if any obstacles in the costmap lie inside a convex footprint that is rasterized into the grid...
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const