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>
|
| 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...
|
|
virtual double | footprintCost (const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius)=0 |
| Subclass will implement this method to check a footprint at a given position and orientation for legality in the world. More...
|
|
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...
|
|
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 | 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...
|
|
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...
|
|
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) |
|
virtual | ~WorldModel () |
| Subclass will implement a destructor. More...
|
|
A class that implements the WorldModel interface to provide grid based collision checks for the trajectory controller using the costmap.
Definition at line 85 of file costmap_model.h.
◆ CostmapModel()
◆ ~CostmapModel()
virtual base_local_planner::CostmapModel::~CostmapModel |
( |
| ) |
|
|
inlinevirtual |
◆ footprintCost() [1/4]
double base_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.
- Parameters
-
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 |
- Returns
- Positive if all the points lie outside the footprint, negative otherwise: -1 if footprint covers at least a lethal obstacle cell, or -2 if footprint covers at least a no-information cell, or -3 if footprint is [partially] outside of the map
Implements base_local_planner::WorldModel.
Definition at line 47 of file costmap_model.cpp.
◆ footprintCost() [2/4]
virtual double base_local_planner::WorldModel::footprintCost |
Subclass will implement this method to check a footprint at a given position and orientation for legality in the world.
- Parameters
-
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 |
- Returns
- Positive if all the points lie outside the footprint, negative otherwise: -1 if footprint covers at least a lethal obstacle cell, or -2 if footprint covers at least a no-information cell, or -3 if footprint is partially or totally outside of the map
◆ footprintCost() [3/4]
double base_local_planner::WorldModel::footprintCost |
|
inline |
Checks if any obstacles in the costmap lie inside a convex footprint that is rasterized into the grid.
- Parameters
-
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 |
- Returns
- Positive if all the points lie outside the footprint, negative otherwise
Definition at line 134 of file world_model.h.
◆ footprintCost() [4/4]
double base_local_planner::WorldModel::footprintCost |
|
inline |
◆ lineCost()
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.
- Parameters
-
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 |
- Returns
- A positive cost for a legal line... negative otherwise
Definition at line 116 of file costmap_model.cpp.
◆ pointCost()
double base_local_planner::CostmapModel::pointCost |
( |
int |
x, |
|
|
int |
y |
|
) |
| const |
Checks the cost of a point in the costmap.
- Parameters
-
x | The x position of the point in cell coordinates |
y | The y position of the point in cell coordinates |
- Returns
- A positive cost for a legal point... negative otherwise
Definition at line 134 of file costmap_model.cpp.
◆ costmap_
Allows access of costmap obstacle information.
Definition at line 133 of file costmap_model.h.
The documentation for this class was generated from the following files: