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. More... | |
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. More... | |
double | lineCost (int x0, int x1, int y0, int y1) const |
Rasterizes a line in the costmap grid and checks for collisions. More... | |
double | pointCost (int x, int y) const |
Checks the cost of a point in the costmap. More... | |
virtual | ~CostmapModel () |
Destructor for the world model. More... | |
Public Member Functions inherited from base_local_planner::WorldModel | |
double | footprintCost (double x, double y, double theta, const std::vector< geometry_msgs::Point > &footprint_spec, double inscribed_radius=0.0, double circumscribed_radius=0.0) |
double | footprintCost (const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius, double extra) |
Checks if any obstacles in the costmap lie inside a convex footprint that is rasterized into the grid. More... | |
virtual | ~WorldModel () |
Subclass will implement a destructor. More... | |
Private Attributes | |
const costmap_2d::Costmap2D & | costmap_ |
Allows access of costmap obstacle information. More... | |
Additional Inherited Members | |
Protected Member Functions inherited from base_local_planner::WorldModel | |
WorldModel () | |
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.
base_local_planner::CostmapModel::CostmapModel | ( | const costmap_2d::Costmap2D & | costmap | ) |
Constructor for the CostmapModel.
costmap | The costmap that should be used |
Definition at line 45 of file costmap_model.cpp.
|
inlinevirtual |
Destructor for the world model.
Definition at line 62 of file costmap_model.h.
|
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 base_local_planner::WorldModel.
Definition at line 47 of file costmap_model.cpp.
double base_local_planner::CostmapModel::lineCost | ( | int | x0, |
int | x1, | ||
int | y0, | ||
int | y1 | ||
) | const |
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 116 of file costmap_model.cpp.
double base_local_planner::CostmapModel::pointCost | ( | int | x, |
int | y | ||
) | const |
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 134 of file costmap_model.cpp.
|
private |
Allows access of costmap obstacle information.
Definition at line 98 of file costmap_model.h.