Classes | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | Friends
costmap_2d::Costmap2D Class Reference

A 2D costmap provides a mapping between points in the world and their associated "costs". More...

#include <costmap_2d.h>

Inheritance diagram for costmap_2d::Costmap2D:
Inheritance graph
[legend]

List of all members.

Classes

class  MarkCell
class  PolygonOutlineCells

Public Types

typedef boost::recursive_mutex mutex_t

Public Member Functions

unsigned int cellDistance (double world_dist)
 Given distance in the world... convert it to cells.
void convexFillCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
 Get the map cells that fill a convex polygon.
bool copyCostmapWindow (const Costmap2D &map, double win_origin_x, double win_origin_y, double win_size_x, double win_size_y)
 Turn this costmap into a copy of a window of a costmap passed in.
 Costmap2D (unsigned int cells_size_x, unsigned int cells_size_y, double resolution, double origin_x, double origin_y, unsigned char default_value=0)
 Constructor for a costmap.
 Costmap2D (const Costmap2D &map)
 Copy constructor for a costmap, creates a copy efficiently.
 Costmap2D ()
 Default constructor.
unsigned char * getCharMap () const
 Will return a pointer to the underlying unsigned char array used as the costmap.
unsigned char getCost (unsigned int mx, unsigned int my) const
 Get the cost of a cell in the costmap.
unsigned char getDefaultValue ()
unsigned int getIndex (unsigned int mx, unsigned int my) const
 Given two map coordinates... compute the associated index.
mutex_tgetMutex ()
double getOriginX () const
 Accessor for the x origin of the costmap.
double getOriginY () const
 Accessor for the y origin of the costmap.
double getResolution () const
 Accessor for the resolution of the costmap.
unsigned int getSizeInCellsX () const
 Accessor for the x size of the costmap in cells.
unsigned int getSizeInCellsY () const
 Accessor for the y size of the costmap in cells.
double getSizeInMetersX () const
 Accessor for the x size of the costmap in meters.
double getSizeInMetersY () const
 Accessor for the y size of the costmap in meters.
void indexToCells (unsigned int index, unsigned int &mx, unsigned int &my) const
 Given an index... compute the associated map coordinates.
void mapToWorld (unsigned int mx, unsigned int my, double &wx, double &wy) const
 Convert from map coordinates to world coordinates.
Costmap2Doperator= (const Costmap2D &map)
 Overloaded assignment operator.
void polygonOutlineCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
 Get the map cells that make up the outline of a polygon.
void resetMap (unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
void resizeMap (unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
bool saveMap (std::string file_name)
 Save the costmap out to a pgm file.
bool setConvexPolygonCost (const std::vector< geometry_msgs::Point > &polygon, unsigned char cost_value)
 Sets the cost of a convex polygon to a desired value.
void setCost (unsigned int mx, unsigned int my, unsigned char cost)
 Set the cost of a cell in the costmap.
void setDefaultValue (unsigned char c)
virtual void updateOrigin (double new_origin_x, double new_origin_y)
 Move the origin of the costmap to a new location.... keeping data when it can.
bool worldToMap (double wx, double wy, unsigned int &mx, unsigned int &my) const
 Convert from world coordinates to map coordinates.
void worldToMapEnforceBounds (double wx, double wy, int &mx, int &my) const
 Convert from world coordinates to map coordinates, constraining results to legal bounds.
void worldToMapNoBounds (double wx, double wy, int &mx, int &my) const
 Convert from world coordinates to map coordinates without checking for legal bounds.
virtual ~Costmap2D ()
 Destructor.

Protected Member Functions

template<typename data_type >
void copyMapRegion (data_type *source_map, unsigned int sm_lower_left_x, unsigned int sm_lower_left_y, unsigned int sm_size_x, data_type *dest_map, unsigned int dm_lower_left_x, unsigned int dm_lower_left_y, unsigned int dm_size_x, unsigned int region_size_x, unsigned int region_size_y)
 Copy a region of a source map into a destination map.
virtual void deleteMaps ()
 Deletes the costmap, static_map, and markers data structures.
virtual void initMaps (unsigned int size_x, unsigned int size_y)
 Initializes the costmap, static_map, and markers data structures.
template<class ActionType >
void raytraceLine (ActionType at, unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, unsigned int max_length=UINT_MAX)
 Raytrace a line and apply some action at each step.
virtual void resetMaps ()
 Resets the costmap and static_map to be unknown space.

Protected Attributes

unsigned char * costmap_
unsigned char default_value_
double origin_x_
double origin_y_
double resolution_
unsigned int size_x_
unsigned int size_y_

Private Member Functions

template<class ActionType >
void bresenham2D (ActionType at, unsigned int abs_da, unsigned int abs_db, int error_b, int offset_a, int offset_b, unsigned int offset, unsigned int max_length)
 A 2D implementation of Bresenham's raytracing algorithm... applies an action at each step.
int sign (int x)

Private Attributes

mutex_taccess_

Friends

class CostmapTester

Detailed Description

A 2D costmap provides a mapping between points in the world and their associated "costs".

Definition at line 60 of file costmap_2d.h.


Member Typedef Documentation

typedef boost::recursive_mutex costmap_2d::Costmap2D::mutex_t

Definition at line 294 of file costmap_2d.h.


Constructor & Destructor Documentation

costmap_2d::Costmap2D::Costmap2D ( unsigned int  cells_size_x,
unsigned int  cells_size_y,
double  resolution,
double  origin_x,
double  origin_y,
unsigned char  default_value = 0 
)

Constructor for a costmap.

Parameters:
cells_size_xThe x size of the map in cells
cells_size_yThe y size of the map in cells
resolutionThe resolution of the map in meters/cell
origin_xThe x origin of the map
origin_yThe y origin of the map
default_valueDefault Value

Definition at line 45 of file costmap_2d.cpp.

Copy constructor for a costmap, creates a copy efficiently.

Parameters:
mapThe costmap to copy

Definition at line 161 of file costmap_2d.cpp.

Default constructor.

Definition at line 169 of file costmap_2d.cpp.

Destructor.

Definition at line 175 of file costmap_2d.cpp.


Member Function Documentation

template<class ActionType >
void costmap_2d::Costmap2D::bresenham2D ( ActionType  at,
unsigned int  abs_da,
unsigned int  abs_db,
int  error_b,
int  offset_a,
int  offset_b,
unsigned int  offset,
unsigned int  max_length 
) [inline, private]

A 2D implementation of Bresenham's raytracing algorithm... applies an action at each step.

Definition at line 396 of file costmap_2d.h.

unsigned int costmap_2d::Costmap2D::cellDistance ( double  world_dist)

Given distance in the world... convert it to cells.

Parameters:
world_distThe world distance
Returns:
The equivalent cell distance

Definition at line 181 of file costmap_2d.cpp.

void costmap_2d::Costmap2D::convexFillCells ( const std::vector< MapLocation > &  polygon,
std::vector< MapLocation > &  polygon_cells 
)

Get the map cells that fill a convex polygon.

Parameters:
polygonThe polygon in map coordinates to rasterize
polygon_cellsWill be set to the cells that fill the polygon

Definition at line 355 of file costmap_2d.cpp.

bool costmap_2d::Costmap2D::copyCostmapWindow ( const Costmap2D map,
double  win_origin_x,
double  win_origin_y,
double  win_size_x,
double  win_size_y 
)

Turn this costmap into a copy of a window of a costmap passed in.

Parameters:
mapThe costmap to copy
win_origin_xThe x origin (lower left corner) for the window to copy, in meters
win_origin_yThe y origin (lower left corner) for the window to copy, in meters
win_size_xThe x size of the window, in meters
win_size_yThe y size of the window, in meters

Definition at line 101 of file costmap_2d.cpp.

template<typename data_type >
void costmap_2d::Costmap2D::copyMapRegion ( data_type *  source_map,
unsigned int  sm_lower_left_x,
unsigned int  sm_lower_left_y,
unsigned int  sm_size_x,
data_type *  dest_map,
unsigned int  dm_lower_left_x,
unsigned int  dm_lower_left_y,
unsigned int  dm_size_x,
unsigned int  region_size_x,
unsigned int  region_size_y 
) [inline, protected]

Copy a region of a source map into a destination map.

Parameters:
source_mapThe source map
sm_lower_left_xThe lower left x point of the source map to start the copy
sm_lower_left_yThe lower left y point of the source map to start the copy
sm_size_xThe x size of the source map
dest_mapThe destination map
dm_lower_left_xThe lower left x point of the destination map to start the copy
dm_lower_left_yThe lower left y point of the destination map to start the copy
dm_size_xThe x size of the destination map
region_size_xThe x size of the region to copy
region_size_yThe y size of the region to copy

Definition at line 315 of file costmap_2d.h.

void costmap_2d::Costmap2D::deleteMaps ( ) [protected, virtual]

Deletes the costmap, static_map, and markers data structures.

Definition at line 57 of file costmap_2d.cpp.

unsigned char * costmap_2d::Costmap2D::getCharMap ( ) const

Will return a pointer to the underlying unsigned char array used as the costmap.

Returns:
A pointer to the underlying unsigned char array storing cost values

Definition at line 187 of file costmap_2d.cpp.

unsigned char costmap_2d::Costmap2D::getCost ( unsigned int  mx,
unsigned int  my 
) const

Get the cost of a cell in the costmap.

Parameters:
mxThe x coordinate of the cell
myThe y coordinate of the cell
Returns:
The cost of the cell

Definition at line 192 of file costmap_2d.cpp.

unsigned char costmap_2d::Costmap2D::getDefaultValue ( ) [inline]

Definition at line 241 of file costmap_2d.h.

unsigned int costmap_2d::Costmap2D::getIndex ( unsigned int  mx,
unsigned int  my 
) const [inline]

Given two map coordinates... compute the associated index.

Parameters:
mxThe x coordinate
myThe y coordinate
Returns:
The associated index

Definition at line 171 of file costmap_2d.h.

Definition at line 295 of file costmap_2d.h.

Accessor for the x origin of the costmap.

Returns:
The x origin of the costmap

Definition at line 446 of file costmap_2d.cpp.

Accessor for the y origin of the costmap.

Returns:
The y origin of the costmap

Definition at line 451 of file costmap_2d.cpp.

Accessor for the resolution of the costmap.

Returns:
The resolution of the costmap

Definition at line 456 of file costmap_2d.cpp.

Accessor for the x size of the costmap in cells.

Returns:
The x size of the costmap

Definition at line 426 of file costmap_2d.cpp.

Accessor for the y size of the costmap in cells.

Returns:
The y size of the costmap

Definition at line 431 of file costmap_2d.cpp.

Accessor for the x size of the costmap in meters.

Returns:
The x size of the costmap (returns the centerpoint of the last legal cell in the map)

Definition at line 436 of file costmap_2d.cpp.

Accessor for the y size of the costmap in meters.

Returns:
The y size of the costmap (returns the centerpoint of the last legal cell in the map)

Definition at line 441 of file costmap_2d.cpp.

void costmap_2d::Costmap2D::indexToCells ( unsigned int  index,
unsigned int &  mx,
unsigned int &  my 
) const [inline]

Given an index... compute the associated map coordinates.

Parameters:
indexThe index
mxWill be set to the x coordinate
myWill be set to the y coordinate

Definition at line 182 of file costmap_2d.h.

void costmap_2d::Costmap2D::initMaps ( unsigned int  size_x,
unsigned int  size_y 
) [protected, virtual]

Initializes the costmap, static_map, and markers data structures.

Parameters:
size_xThe x size to use for map initialization
size_yThe y size to use for map initialization

Definition at line 65 of file costmap_2d.cpp.

void costmap_2d::Costmap2D::mapToWorld ( unsigned int  mx,
unsigned int  my,
double &  wx,
double &  wy 
) const

Convert from map coordinates to world coordinates.

Parameters:
mxThe x map coordinate
myThe y map coordinate
wxWill be set to the associated world x coordinate
wyWill be set to the associated world y coordinate

Definition at line 202 of file costmap_2d.cpp.

Costmap2D & costmap_2d::Costmap2D::operator= ( const Costmap2D map)

Overloaded assignment operator.

Parameters:
mapThe costmap to copy
Returns:
A reference to the map after the copy has finished

Definition at line 137 of file costmap_2d.cpp.

void costmap_2d::Costmap2D::polygonOutlineCells ( const std::vector< MapLocation > &  polygon,
std::vector< MapLocation > &  polygon_cells 
)

Get the map cells that make up the outline of a polygon.

Parameters:
polygonThe polygon in map coordinates to rasterize
polygon_cellsWill be set to the cells contained in the outline of the polygon

Definition at line 340 of file costmap_2d.cpp.

template<class ActionType >
void costmap_2d::Costmap2D::raytraceLine ( ActionType  at,
unsigned int  x0,
unsigned int  y0,
unsigned int  x1,
unsigned int  y1,
unsigned int  max_length = UINT_MAX 
) [inline, protected]

Raytrace a line and apply some action at each step.

Parameters:
atThe action to take... a functor
x0The starting x coordinate
y0The starting y coordinate
x1The ending x coordinate
y1The ending y coordinate
max_lengthThe maximum desired length of the segment... allows you to not go all the way to the endpoint

Definition at line 360 of file costmap_2d.h.

void costmap_2d::Costmap2D::resetMap ( unsigned int  x0,
unsigned int  y0,
unsigned int  xn,
unsigned int  yn 
)

Definition at line 93 of file costmap_2d.cpp.

void costmap_2d::Costmap2D::resetMaps ( ) [protected, virtual]

Resets the costmap and static_map to be unknown space.

Reimplemented in costmap_2d::VoxelLayer.

Definition at line 87 of file costmap_2d.cpp.

void costmap_2d::Costmap2D::resizeMap ( unsigned int  size_x,
unsigned int  size_y,
double  resolution,
double  origin_x,
double  origin_y 
)

Definition at line 72 of file costmap_2d.cpp.

bool costmap_2d::Costmap2D::saveMap ( std::string  file_name)

Save the costmap out to a pgm file.

Parameters:
file_nameThe name of the file to save

Definition at line 461 of file costmap_2d.cpp.

bool costmap_2d::Costmap2D::setConvexPolygonCost ( const std::vector< geometry_msgs::Point > &  polygon,
unsigned char  cost_value 
)

Sets the cost of a convex polygon to a desired value.

Parameters:
polygonThe polygon to perform the operation on
cost_valueThe value to set costs to
Returns:
True if the polygon was filled... false if it could not be filled

Definition at line 311 of file costmap_2d.cpp.

void costmap_2d::Costmap2D::setCost ( unsigned int  mx,
unsigned int  my,
unsigned char  cost 
)

Set the cost of a cell in the costmap.

Parameters:
mxThe x coordinate of the cell
myThe y coordinate of the cell
costThe cost to set the cell to

Definition at line 197 of file costmap_2d.cpp.

void costmap_2d::Costmap2D::setDefaultValue ( unsigned char  c) [inline]

Definition at line 236 of file costmap_2d.h.

int costmap_2d::Costmap2D::sign ( int  x) [inline, private]

Definition at line 414 of file costmap_2d.h.

void costmap_2d::Costmap2D::updateOrigin ( double  new_origin_x,
double  new_origin_y 
) [virtual]

Move the origin of the costmap to a new location.... keeping data when it can.

Parameters:
new_origin_xThe x coordinate of the new origin
new_origin_yThe y coordinate of the new origin

Reimplemented in costmap_2d::VoxelLayer.

Definition at line 260 of file costmap_2d.cpp.

bool costmap_2d::Costmap2D::worldToMap ( double  wx,
double  wy,
unsigned int &  mx,
unsigned int &  my 
) const

Convert from world coordinates to map coordinates.

Parameters:
wxThe x world coordinate
wyThe y world coordinate
mxWill be set to the associated map x coordinate
myWill be set to the associated map y coordinate
Returns:
True if the conversion was successful (legal bounds) false otherwise

Definition at line 208 of file costmap_2d.cpp.

void costmap_2d::Costmap2D::worldToMapEnforceBounds ( double  wx,
double  wy,
int &  mx,
int &  my 
) const

Convert from world coordinates to map coordinates, constraining results to legal bounds.

Parameters:
wxThe x world coordinate
wyThe y world coordinate
mxWill be set to the associated map x coordinate
myWill be set to the associated map y coordinate
Note:
The returned map coordinates are guaranteed to lie within the map.

Definition at line 228 of file costmap_2d.cpp.

void costmap_2d::Costmap2D::worldToMapNoBounds ( double  wx,
double  wy,
int &  mx,
int &  my 
) const

Convert from world coordinates to map coordinates without checking for legal bounds.

Parameters:
wxThe x world coordinate
wyThe y world coordinate
mxWill be set to the associated map x coordinate
myWill be set to the associated map y coordinate
Note:
The returned map coordinates are not guaranteed to lie within the map.

Definition at line 222 of file costmap_2d.cpp.


Friends And Related Function Documentation

friend class CostmapTester [friend]

Definition at line 62 of file costmap_2d.h.


Member Data Documentation

Definition at line 419 of file costmap_2d.h.

unsigned char* costmap_2d::Costmap2D::costmap_ [protected]

Definition at line 426 of file costmap_2d.h.

unsigned char costmap_2d::Costmap2D::default_value_ [protected]

Definition at line 427 of file costmap_2d.h.

Definition at line 424 of file costmap_2d.h.

Definition at line 425 of file costmap_2d.h.

Definition at line 423 of file costmap_2d.h.

unsigned int costmap_2d::Costmap2D::size_x_ [protected]

Definition at line 421 of file costmap_2d.h.

unsigned int costmap_2d::Costmap2D::size_y_ [protected]

Definition at line 422 of file costmap_2d.h.


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


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:46:15