Public Member Functions | Private Member Functions | Private Attributes
base_local_planner::CostmapModel Class Reference

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>

Inheritance diagram for base_local_planner::CostmapModel:
Inheritance graph
[legend]

List of all members.

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::Costmap2Dcostmap_
 Allows access of costmap obstacle information.

Detailed Description

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.


Constructor & Destructor Documentation

Constructor for the CostmapModel.

Parameters:
costmapThe costmap that should be used
Returns:

Definition at line 45 of file costmap_model.cpp.

virtual base_local_planner::CostmapModel::~CostmapModel ( ) [inline, virtual]

Destructor for the world model.

Definition at line 62 of file costmap_model.h.


Member Function Documentation

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:
positionThe position of the robot in world coordinates
footprintThe specification of the footprint of the robot in world coordinates
inscribed_radiusThe radius of the inscribed circle of the robot
circumscribed_radiusThe radius of the circumscribed circle of the robot
Returns:
Positive if all the points lie outside the footprint, negative otherwise

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 
) [private]

Rasterizes a line in the costmap grid and checks for collisions.

Parameters:
x0The x position of the first cell in grid coordinates
y0The y position of the first cell in grid coordinates
x1The x position of the second cell in grid coordinates
y1The y position of the second cell in grid coordinates
Returns:
A positive cost for a legal line... negative otherwise

Definition at line 110 of file costmap_model.cpp.

double base_local_planner::CostmapModel::pointCost ( int  x,
int  y 
) [private]

Checks the cost of a point in the costmap.

Parameters:
xThe x position of the point in cell coordinates
yThe y position of the point in cell coordinates
Returns:
A positive cost for a legal point... negative otherwise

Definition at line 130 of file costmap_model.cpp.


Member Data Documentation

Allows access of costmap obstacle information.

Definition at line 95 of file costmap_model.h.


The documentation for this class was generated from the following files:


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Wed Aug 2 2017 03:12:38