Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
Classes | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
nav2_costmap_2d::Costmap2D Class Reference

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

#include <nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d.hpp>

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

Classes

class  MarkCell
 
class  PolygonOutlineCells
 

Public Types

typedef std::recursive_mutex mutex_t
 

Public Member Functions

 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. More...
 
 Costmap2D (const Costmap2D &map)
 Copy constructor for a costmap, creates a copy efficiently. More...
 
 Costmap2D (const nav_msgs::msg::OccupancyGrid &map)
 Constructor for a costmap from an OccupancyGrid map. More...
 
Costmap2Doperator= (const Costmap2D &map)
 Overloaded assignment operator. More...
 
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. More...
 
bool copyWindow (const Costmap2D &source, unsigned int sx0, unsigned int sy0, unsigned int sxn, unsigned int syn, unsigned int dx0, unsigned int dy0)
 Copies the (x0,y0)..(xn,yn) window from source costmap into a current costmap. More...
 
 Costmap2D ()
 Default constructor.
 
virtual ~Costmap2D ()
 Destructor.
 
unsigned char getCost (unsigned int mx, unsigned int my) const
 Get the cost of a cell in the costmap. More...
 
unsigned char getCost (unsigned int index) const
 Get the cost of a cell in the costmap. More...
 
void setCost (unsigned int mx, unsigned int my, unsigned char cost)
 Set the cost of a cell in the costmap. More...
 
void mapToWorld (unsigned int mx, unsigned int my, double &wx, double &wy) const
 Convert from map coordinates to world coordinates. More...
 
bool worldToMap (double wx, double wy, unsigned int &mx, unsigned int &my) const
 Convert from world coordinates to map coordinates. More...
 
void worldToMapNoBounds (double wx, double wy, int &mx, int &my) const
 Convert from world coordinates to map coordinates without checking for legal bounds. More...
 
void worldToMapEnforceBounds (double wx, double wy, int &mx, int &my) const
 Convert from world coordinates to map coordinates, constraining results to legal bounds. More...
 
unsigned int getIndex (unsigned int mx, unsigned int my) const
 Given two map coordinates... compute the associated index. More...
 
void indexToCells (unsigned int index, unsigned int &mx, unsigned int &my) const
 Given an index... compute the associated map coordinates. More...
 
unsigned char * getCharMap () const
 Will return a pointer to the underlying unsigned char array used as the costmap. More...
 
unsigned int getSizeInCellsX () const
 Accessor for the x size of the costmap in cells. More...
 
unsigned int getSizeInCellsY () const
 Accessor for the y size of the costmap in cells. More...
 
double getSizeInMetersX () const
 Accessor for the x size of the costmap in meters. More...
 
double getSizeInMetersY () const
 Accessor for the y size of the costmap in meters. More...
 
double getOriginX () const
 Accessor for the x origin of the costmap. More...
 
double getOriginY () const
 Accessor for the y origin of the costmap. More...
 
double getResolution () const
 Accessor for the resolution of the costmap. More...
 
void setDefaultValue (unsigned char c)
 Set the default background value of the costmap. More...
 
unsigned char getDefaultValue ()
 Get the default background value of the costmap. More...
 
bool setConvexPolygonCost (const std::vector< geometry_msgs::msg::Point > &polygon, unsigned char cost_value)
 Sets the cost of a convex polygon to a desired value. More...
 
void polygonOutlineCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
 Get the map cells that make up the outline of a polygon. More...
 
void convexFillCells (const std::vector< MapLocation > &polygon, std::vector< MapLocation > &polygon_cells)
 Get the map cells that fill a convex polygon. More...
 
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. More...
 
bool saveMap (std::string file_name)
 Save the costmap out to a pgm file. More...
 
void resizeMap (unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
 Resize the costmap.
 
void resetMap (unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn)
 Reset the costmap in bounds.
 
void resetMapToValue (unsigned int x0, unsigned int y0, unsigned int xn, unsigned int yn, unsigned char value)
 Reset the costmap in bounds to a value.
 
unsigned int cellDistance (double world_dist)
 Given distance in the world... convert it to cells. More...
 
mutex_t * getMutex ()
 

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. More...
 
virtual void deleteMaps ()
 Deletes the costmap, static_map, and markers data structures.
 
virtual void resetMaps ()
 Resets the costmap and static_map to be unknown space.
 
virtual void initMaps (unsigned int size_x, unsigned int size_y)
 Initializes the costmap, static_map, and markers data structures. More...
 
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, unsigned int min_length=0)
 Raytrace a line and apply some action at each step. More...
 

Protected Attributes

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

Friends

class CostmapTester
 

Detailed Description

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

Definition at line 67 of file costmap_2d.hpp.

Constructor & Destructor Documentation

◆ Costmap2D() [1/3]

nav2_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 49 of file costmap_2d.cpp.

References initMaps(), and resetMaps().

Here is the call graph for this function:

◆ Costmap2D() [2/3]

nav2_costmap_2d::Costmap2D::Costmap2D ( const Costmap2D map)

Copy constructor for a costmap, creates a copy efficiently.

Parameters
mapThe costmap to copy

Definition at line 235 of file costmap_2d.cpp.

◆ Costmap2D() [3/3]

nav2_costmap_2d::Costmap2D::Costmap2D ( const nav_msgs::msg::OccupancyGrid &  map)
explicit

Constructor for a costmap from an OccupancyGrid map.

Parameters
mapThe OccupancyGrid map to create costmap from

Definition at line 62 of file costmap_2d.cpp.

Member Function Documentation

◆ cellDistance()

unsigned int nav2_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 255 of file costmap_2d.cpp.

Referenced by nav2_costmap_2d::InflationLayer::cellDistance(), nav2_costmap_2d::ObstacleLayer::raytraceFreespace(), and nav2_costmap_2d::VoxelLayer::raytraceFreespace().

Here is the caller graph for this function:

◆ convexFillCells()

void nav2_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 432 of file costmap_2d.cpp.

References polygonOutlineCells().

Referenced by setConvexPolygonCost().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ copyCostmapWindow()

bool nav2_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 145 of file costmap_2d.cpp.

References copyMapRegion(), deleteMaps(), initMaps(), and worldToMap().

Here is the call graph for this function:

◆ copyMapRegion()

template<typename data_type >
void nav2_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 
)
inlineprotected

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 382 of file costmap_2d.hpp.

Referenced by copyCostmapWindow(), copyWindow(), updateOrigin(), and nav2_costmap_2d::VoxelLayer::updateOrigin().

Here is the caller graph for this function:

◆ copyWindow()

bool nav2_costmap_2d::Costmap2D::copyWindow ( const Costmap2D source,
unsigned int  sx0,
unsigned int  sy0,
unsigned int  sxn,
unsigned int  syn,
unsigned int  dx0,
unsigned int  dy0 
)

Copies the (x0,y0)..(xn,yn) window from source costmap into a current costmap.

Parameters
sourceSource costmap where the window will be copied from
sx0Lower x-boundary of the source window to copy, in cells
sy0Lower y-boundary of the source window to copy, in cells
sxnUpper x-boundary of the source window to copy, in cells
synUpper y-boundary of the source window to copy, in cells
dx0Lower x-boundary of the destination window to copy, in cells
dx0Lower y-boundary of the destination window to copy, in cells
Returns
true if copy was succeeded or false in negative case

Definition at line 187 of file costmap_2d.cpp.

References copyMapRegion(), getSizeInCellsX(), and getSizeInCellsY().

Referenced by nav2_costmap_2d::LayeredCostmap::updateMap().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getCharMap()

unsigned char * nav2_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 261 of file costmap_2d.cpp.

Referenced by nav2_costmap_2d::CostmapLayer::clearArea(), nav2_navfn_planner::NavfnPlanner::makePlan(), nav2_costmap_2d::KeepoutFilter::process(), nav2_costmap_2d::RangeSensorLayer::updateCosts(), nav2_costmap_2d::InflationLayer::updateCosts(), and nav2_costmap_2d::DenoiseLayer::updateCosts().

Here is the caller graph for this function:

◆ getCost() [1/2]

unsigned char nav2_costmap_2d::Costmap2D::getCost ( unsigned int  index) const

Get the cost of a cell in the costmap.

Parameters
indexThe cell index
Returns
The cost of the cell

Definition at line 271 of file costmap_2d.cpp.

◆ getCost() [2/2]

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

◆ getDefaultValue()

unsigned char nav2_costmap_2d::Costmap2D::getDefaultValue ( )
inline

Get the default background value of the costmap.

Returns
default value

Definition at line 289 of file costmap_2d.hpp.

Referenced by nav2_costmap_2d::ClearCostmapService::ClearCostmapService(), nav2_costmap_2d::LayeredCostmap::isTrackingUnknown(), and nav2_costmap_2d::DenoiseLayer::updateCosts().

Here is the caller graph for this function:

◆ getIndex()

unsigned int nav2_costmap_2d::Costmap2D::getIndex ( unsigned int  mx,
unsigned int  my 
) const
inline

◆ getOriginX()

double nav2_costmap_2d::Costmap2D::getOriginX ( ) const

◆ getOriginY()

double nav2_costmap_2d::Costmap2D::getOriginY ( ) const

◆ getResolution()

double nav2_costmap_2d::Costmap2D::getResolution ( ) const

◆ getSizeInCellsX()

unsigned int nav2_costmap_2d::Costmap2D::getSizeInCellsX ( ) const

Accessor for the x size of the costmap in cells.

Returns
The x size of the costmap

Definition at line 501 of file costmap_2d.cpp.

Referenced by dwb_critics::BaseObstacleCritic::addCriticVisualization(), dwb_critics::MapGridCritic::addCriticVisualization(), nav2_costmap_2d::CostmapLayer::clearArea(), costmap_queue::CostmapQueue::computeCache(), nav2_navfn_planner::NavfnPlanner::configure(), copyWindow(), nav2_costmap_2d::Costmap2DPublisher::Costmap2DPublisher(), nav2_navfn_planner::NavfnPlanner::createPlan(), costmap_queue::CostmapQueue::getNextCell(), nav2_smac_planner::NodeHybrid::getObstacleHeuristic(), nav2_navfn_planner::NavfnPlanner::getPlanFromPotential(), nav2_smac_planner::GridCollisionChecker::inCollision(), nav2_navfn_planner::NavfnPlanner::isPlannerOutOfDate(), nav2_navfn_planner::NavfnPlanner::makePlan(), nav2_costmap_2d::CostmapLayer::matchSize(), nav2_costmap_2d::StaticLayer::matchSize(), nav2_costmap_2d::InflationLayer::matchSize(), nav2_planner::PlannerServer::on_configure(), nav2_costmap_2d::StaticLayer::processMap(), nav2_costmap_2d::Costmap2DPublisher::publishCostmap(), costmap_queue::CostmapQueue::reset(), dwb_critics::MapGridCritic::reset(), nav2_costmap_2d::Costmap2DROS::resetLayers(), nav2_smac_planner::NodeHybrid::resetObstacleHeuristic(), nav2_smac_planner::AStarAlgorithm< NodeT >::setCollisionChecker(), dwb_core::DWBLocalPlanner::transformGlobalPlan(), nav2_smac_planner::CostmapDownsampler::updateCostmapSize(), nav2_costmap_2d::RangeSensorLayer::updateCosts(), nav2_costmap_2d::InflationLayer::updateCosts(), nav2_costmap_2d::DenoiseLayer::updateCosts(), nav2_costmap_2d::LayeredCostmap::updateMap(), and nav2_navfn_planner::NavfnPlanner::worldToMap().

Here is the caller graph for this function:

◆ getSizeInCellsY()

unsigned int nav2_costmap_2d::Costmap2D::getSizeInCellsY ( ) const

Accessor for the y size of the costmap in cells.

Returns
The y size of the costmap

Definition at line 506 of file costmap_2d.cpp.

Referenced by dwb_critics::BaseObstacleCritic::addCriticVisualization(), dwb_critics::MapGridCritic::addCriticVisualization(), nav2_costmap_2d::CostmapLayer::clearArea(), costmap_queue::CostmapQueue::computeCache(), nav2_navfn_planner::NavfnPlanner::configure(), copyWindow(), nav2_costmap_2d::Costmap2DPublisher::Costmap2DPublisher(), nav2_navfn_planner::NavfnPlanner::createPlan(), costmap_queue::CostmapQueue::getNextCell(), nav2_smac_planner::NodeHybrid::getObstacleHeuristic(), nav2_navfn_planner::NavfnPlanner::getPlanFromPotential(), nav2_smac_planner::GridCollisionChecker::inCollision(), nav2_navfn_planner::NavfnPlanner::isPlannerOutOfDate(), nav2_navfn_planner::NavfnPlanner::makePlan(), nav2_costmap_2d::CostmapLayer::matchSize(), nav2_costmap_2d::StaticLayer::matchSize(), nav2_costmap_2d::InflationLayer::matchSize(), nav2_planner::PlannerServer::on_configure(), nav2_costmap_2d::StaticLayer::processMap(), nav2_costmap_2d::Costmap2DPublisher::publishCostmap(), costmap_queue::CostmapQueue::reset(), dwb_critics::MapGridCritic::reset(), nav2_costmap_2d::Costmap2DROS::resetLayers(), nav2_smac_planner::NodeHybrid::resetObstacleHeuristic(), dwb_core::DWBLocalPlanner::transformGlobalPlan(), nav2_smac_planner::CostmapDownsampler::updateCostmapSize(), nav2_costmap_2d::InflationLayer::updateCosts(), nav2_costmap_2d::LayeredCostmap::updateMap(), and nav2_navfn_planner::NavfnPlanner::worldToMap().

Here is the caller graph for this function:

◆ getSizeInMetersX()

double nav2_costmap_2d::Costmap2D::getSizeInMetersX ( ) const

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 511 of file costmap_2d.cpp.

Referenced by nav2_costmap_2d::ObstacleLayer::raytraceFreespace(), nav2_costmap_2d::VoxelLayer::raytraceFreespace(), nav2_costmap_2d::ObstacleLayer::updateBounds(), nav2_costmap_2d::VoxelLayer::updateBounds(), and nav2_costmap_2d::LayeredCostmap::updateMap().

Here is the caller graph for this function:

◆ getSizeInMetersY()

double nav2_costmap_2d::Costmap2D::getSizeInMetersY ( ) const

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 516 of file costmap_2d.cpp.

Referenced by nav2_costmap_2d::ObstacleLayer::raytraceFreespace(), nav2_costmap_2d::VoxelLayer::raytraceFreespace(), nav2_costmap_2d::ObstacleLayer::updateBounds(), nav2_costmap_2d::VoxelLayer::updateBounds(), and nav2_costmap_2d::LayeredCostmap::updateMap().

Here is the caller graph for this function:

◆ indexToCells()

void nav2_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 222 of file costmap_2d.hpp.

◆ initMaps()

void nav2_costmap_2d::Costmap2D::initMaps ( unsigned int  size_x,
unsigned int  size_y 
)
protectedvirtual

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 101 of file costmap_2d.cpp.

Referenced by copyCostmapWindow(), Costmap2D(), operator=(), and resizeMap().

Here is the caller graph for this function:

◆ mapToWorld()

void nav2_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 281 of file costmap_2d.cpp.

Referenced by nav2_smac_planner::GridCollisionChecker::inCollision(), nav2_costmap_2d::KeepoutFilter::process(), nav2_costmap_2d::StaticLayer::updateBounds(), and nav2_costmap_2d::StaticLayer::updateCosts().

Here is the caller graph for this function:

◆ operator=()

Costmap2D & nav2_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 210 of file costmap_2d.cpp.

References deleteMaps(), and initMaps().

Here is the call graph for this function:

◆ polygonOutlineCells()

void nav2_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 415 of file costmap_2d.cpp.

References raytraceLine().

Referenced by convexFillCells().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ raytraceLine()

template<class ActionType >
void nav2_costmap_2d::Costmap2D::raytraceLine ( ActionType  at,
unsigned int  x0,
unsigned int  y0,
unsigned int  x1,
unsigned int  y1,
unsigned int  max_length = UINT_MAX,
unsigned int  min_length = 0 
)
inlineprotected

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
min_lengthThe minimum desired length of the segment

Definition at line 430 of file costmap_2d.hpp.

Referenced by polygonOutlineCells(), and nav2_costmap_2d::ObstacleLayer::raytraceFreespace().

Here is the caller graph for this function:

◆ saveMap()

bool nav2_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 536 of file costmap_2d.cpp.

References getCost().

Here is the call graph for this function:

◆ setConvexPolygonCost()

bool nav2_costmap_2d::Costmap2D::setConvexPolygonCost ( const std::vector< geometry_msgs::msg::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 386 of file costmap_2d.cpp.

References convexFillCells(), getIndex(), and worldToMap().

Referenced by nav2_costmap_2d::ObstacleLayer::updateCosts(), and nav2_costmap_2d::StaticLayer::updateCosts().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setCost()

void nav2_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 276 of file costmap_2d.cpp.

References getIndex().

Referenced by nav2_navfn_planner::NavfnPlanner::clearRobotCell(), and nav2_costmap_2d::StaticLayer::updateCosts().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setDefaultValue()

void nav2_costmap_2d::Costmap2D::setDefaultValue ( unsigned char  c)
inline

Set the default background value of the costmap.

Parameters
cdefault value

Definition at line 280 of file costmap_2d.hpp.

Referenced by nav2_costmap_2d::LayeredCostmap::LayeredCostmap().

Here is the caller graph for this function:

◆ updateOrigin()

void nav2_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 nav2_costmap_2d::VoxelLayer.

Definition at line 330 of file costmap_2d.cpp.

References copyMapRegion(), and resetMaps().

Referenced by nav2_costmap_2d::ObstacleLayer::updateBounds(), and nav2_costmap_2d::LayeredCostmap::updateMap().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ worldToMap()

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

◆ worldToMapEnforceBounds()

void nav2_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 308 of file costmap_2d.cpp.

Referenced by nav2_costmap_2d::LayeredCostmap::updateMap().

Here is the caller graph for this function:

◆ worldToMapNoBounds()

void nav2_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 302 of file costmap_2d.cpp.

Referenced by nav2_costmap_2d::KeepoutFilter::process().

Here is the caller graph for this function:

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