A class that implements the WorldModel interface to provide grid based collision checks for the trajectory controller using the costmap. More...
#include <costmap_model.h>

| Public Member Functions | |
| CostmapModel (const costmap_2d::Costmap2D &costmap) | |
| Constructor for the CostmapModel. | |
| 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. | |
| virtual | ~CostmapModel () | 
| Destructor for the world model. | |
| Private Member Functions | |
| double | lineCost (int x0, int x1, int y0, int y1) | 
| Rasterizes a line in the costmap grid and checks for collisions. | |
| double | pointCost (int x, int y) | 
| Checks the cost of a point in the costmap. | |
| Private Attributes | |
| const costmap_2d::Costmap2D & | costmap_ | 
| Allows access of costmap obstacle information. | |
A class that implements the WorldModel interface to provide grid based collision checks for the trajectory controller using the costmap.
Definition at line 50 of file costmap_model.h.
| iri_diff_local_planner::CostmapModel::CostmapModel | ( | const costmap_2d::Costmap2D & | costmap | ) | 
Constructor for the CostmapModel.
| costmap | The costmap that should be used | 
Definition at line 43 of file costmap_model.cpp.
| virtual iri_diff_local_planner::CostmapModel::~CostmapModel | ( | ) |  [inline, virtual] | 
Destructor for the world model.
Definition at line 62 of file costmap_model.h.
| virtual double iri_diff_local_planner::CostmapModel::footprintCost | ( | const geometry_msgs::Point & | position, | 
| const std::vector< geometry_msgs::Point > & | footprint, | ||
| double | inscribed_radius, | ||
| double | circumscribed_radius | ||
| ) |  [virtual] | 
Checks if any obstacles in the costmap lie inside a convex footprint that is rasterized into the grid.
| position | The position of the robot in world coordinates | 
| footprint | The specification of the footprint of the robot in world coordinates | 
| inscribed_radius | The radius of the inscribed circle of the robot | 
| circumscribed_radius | The radius of the circumscribed circle of the robot | 
Implements iri_diff_local_planner::WorldModel.
| double iri_diff_local_planner::CostmapModel::lineCost | ( | int | x0, | 
| int | x1, | ||
| int | y0, | ||
| int | y1 | ||
| ) |  [private] | 
Rasterizes a line in the costmap grid and checks for collisions.
| x0 | The x position of the first cell in grid coordinates | 
| y0 | The y position of the first cell in grid coordinates | 
| x1 | The x position of the second cell in grid coordinates | 
| y1 | The y position of the second cell in grid coordinates | 
Definition at line 107 of file costmap_model.cpp.
| double iri_diff_local_planner::CostmapModel::pointCost | ( | int | x, | 
| int | y | ||
| ) |  [private] | 
Checks the cost of a point in the costmap.
| x | The x position of the point in cell coordinates | 
| y | The y position of the point in cell coordinates | 
Definition at line 186 of file costmap_model.cpp.
| const costmap_2d::Costmap2D& iri_diff_local_planner::CostmapModel::costmap_  [private] | 
Allows access of costmap obstacle information.
Definition at line 94 of file costmap_model.h.