|
Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
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>

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... | |
| Costmap2D & | operator= (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 |
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition at line 67 of file costmap_2d.hpp.
| 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.
| cells_size_x | The x size of the map in cells |
| cells_size_y | The y size of the map in cells |
| resolution | The resolution of the map in meters/cell |
| origin_x | The x origin of the map |
| origin_y | The y origin of the map |
| default_value | Default Value |
Definition at line 49 of file costmap_2d.cpp.
References initMaps(), and resetMaps().

| nav2_costmap_2d::Costmap2D::Costmap2D | ( | const Costmap2D & | map | ) |
Copy constructor for a costmap, creates a copy efficiently.
| map | The costmap to copy |
Definition at line 235 of file costmap_2d.cpp.
|
explicit |
Constructor for a costmap from an OccupancyGrid map.
| map | The OccupancyGrid map to create costmap from |
Definition at line 62 of file costmap_2d.cpp.
| unsigned int nav2_costmap_2d::Costmap2D::cellDistance | ( | double | world_dist | ) |
Given distance in the world... convert it to cells.
| world_dist | The world 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().

| 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.
| polygon | The polygon in map coordinates to rasterize |
| polygon_cells | Will be set to the cells that fill the polygon |
Definition at line 432 of file costmap_2d.cpp.
References polygonOutlineCells().
Referenced by setConvexPolygonCost().


| 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.
| map | The costmap to copy |
| win_origin_x | The x origin (lower left corner) for the window to copy, in meters |
| win_origin_y | The y origin (lower left corner) for the window to copy, in meters |
| win_size_x | The x size of the window, in meters |
| win_size_y | The y size of the window, in meters |
Definition at line 145 of file costmap_2d.cpp.
References copyMapRegion(), deleteMaps(), initMaps(), and worldToMap().

|
inlineprotected |
Copy a region of a source map into a destination map.
| source_map | The source map |
| sm_lower_left_x | The lower left x point of the source map to start the copy |
| sm_lower_left_y | The lower left y point of the source map to start the copy |
| sm_size_x | The x size of the source map |
| dest_map | The destination map |
| dm_lower_left_x | The lower left x point of the destination map to start the copy |
| dm_lower_left_y | The lower left y point of the destination map to start the copy |
| dm_size_x | The x size of the destination map |
| region_size_x | The x size of the region to copy |
| region_size_y | The 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().

| 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.
| source | Source costmap where the window will be copied from |
| sx0 | Lower x-boundary of the source window to copy, in cells |
| sy0 | Lower y-boundary of the source window to copy, in cells |
| sxn | Upper x-boundary of the source window to copy, in cells |
| syn | Upper y-boundary of the source window to copy, in cells |
| dx0 | Lower x-boundary of the destination window to copy, in cells |
| dx0 | Lower y-boundary of the destination window to copy, in cells |
Definition at line 187 of file costmap_2d.cpp.
References copyMapRegion(), getSizeInCellsX(), and getSizeInCellsY().
Referenced by nav2_costmap_2d::LayeredCostmap::updateMap().


| unsigned char * nav2_costmap_2d::Costmap2D::getCharMap | ( | ) | const |
Will return a pointer to the underlying unsigned char array used as the costmap.
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().

| unsigned char nav2_costmap_2d::Costmap2D::getCost | ( | unsigned int | index | ) | const |
Get the cost of a cell in the costmap.
| index | The cell index |
Definition at line 271 of file costmap_2d.cpp.
| unsigned char nav2_costmap_2d::Costmap2D::getCost | ( | unsigned int | mx, |
| unsigned int | my | ||
| ) | const |
Get the cost of a cell in the costmap.
| mx | The x coordinate of the cell |
| my | The y coordinate of the cell |
Definition at line 266 of file costmap_2d.cpp.
References getIndex().
Referenced by dwb_critics::BaseObstacleCritic::addCriticVisualization(), nav2_navfn_planner::NavfnPlanner::createPlan(), nav2_smac_planner::SmacPlanner2D::createPlan(), nav2_smac_planner::Smoother::findBoundaryExpansion(), nav2_smac_planner::NodeHybrid::getObstacleHeuristic(), nav2_smac_planner::GridCollisionChecker::inCollision(), nav2_planner::PlannerServer::isPathValid(), theta_star::ThetaStar::isSafe(), dwb_critics::ObstacleFootprintCritic::pointCost(), dwb_critics::PathDistCritic::prepare(), nav2_costmap_2d::Costmap2DPublisher::publishCostmap(), saveMap(), dwb_critics::BaseObstacleCritic::scorePose(), nav2_smac_planner::CostmapDownsampler::setCostOfCell(), nav2_smac_planner::Smoother::smoothImpl(), nav2_smoother::SimpleSmoother::smoothImpl(), and nav2_costmap_2d::StaticLayer::updateCosts().


|
inline |
Get the default background value of the costmap.
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().

|
inline |
Given two map coordinates... compute the associated index.
| mx | The x coordinate |
| my | The y coordinate |
Definition at line 211 of file costmap_2d.hpp.
Referenced by nav2_costmap_2d::CostmapLayer::clearArea(), costmap_queue::CostmapQueue::enqueueCell(), getCost(), nav2_simple_commander.costmap_2d.PyCostmap2D::getCostXY(), dwb_critics::MapGridCritic::getScore(), dwb_critics::GoalDistCritic::prepare(), dwb_critics::PathDistCritic::prepare(), nav2_costmap_2d::KeepoutFilter::process(), setConvexPolygonCost(), nav2_simple_commander.costmap_2d.PyCostmap2D::setCost(), setCost(), nav2_costmap_2d::ObstacleLayer::updateBounds(), nav2_costmap_2d::VoxelLayer::updateBounds(), and nav2_costmap_2d::InflationLayer::updateCosts().

| double nav2_costmap_2d::Costmap2D::getOriginX | ( | ) | const |
Accessor for the x origin of the costmap.
Definition at line 521 of file costmap_2d.cpp.
Referenced by nav2_navfn_planner::NavfnPlanner::mapToWorld(), nav2_costmap_2d::CostmapLayer::matchSize(), nav2_costmap_2d::StaticLayer::matchSize(), nav2_smac_planner::CostmapDownsampler::on_configure(), nav2_costmap_2d::StaticLayer::processMap(), nav2_costmap_2d::Costmap2DPublisher::publishCostmap(), nav2_smac_planner::CostmapDownsampler::resizeCostmap(), and nav2_navfn_planner::NavfnPlanner::worldToMap().

| double nav2_costmap_2d::Costmap2D::getOriginY | ( | ) | const |
Accessor for the y origin of the costmap.
Definition at line 526 of file costmap_2d.cpp.
Referenced by nav2_navfn_planner::NavfnPlanner::mapToWorld(), nav2_costmap_2d::CostmapLayer::matchSize(), nav2_costmap_2d::StaticLayer::matchSize(), nav2_smac_planner::CostmapDownsampler::on_configure(), nav2_costmap_2d::StaticLayer::processMap(), nav2_costmap_2d::Costmap2DPublisher::publishCostmap(), nav2_smac_planner::CostmapDownsampler::resizeCostmap(), and nav2_navfn_planner::NavfnPlanner::worldToMap().

| double nav2_costmap_2d::Costmap2D::getResolution | ( | ) | const |
Accessor for the resolution of the costmap.
Definition at line 531 of file costmap_2d.cpp.
Referenced by nav2_smac_planner::SmacPlannerHybrid::configure(), nav2_smac_planner::SmacPlannerLattice::configure(), nav2_smac_planner::SmacPlanner2D::createPlan(), nav2_smac_planner::SmacPlannerHybrid::createPlan(), nav2_smac_planner::SmacPlannerLattice::createPlan(), nav2_smac_planner::SmacPlannerHybrid::dynamicParametersCallback(), nav2_smac_planner::SmacPlannerLattice::dynamicParametersCallback(), nav2_navfn_planner::NavfnPlanner::makePlan(), nav2_navfn_planner::NavfnPlanner::mapToWorld(), nav2_costmap_2d::CostmapLayer::matchSize(), nav2_costmap_2d::StaticLayer::matchSize(), nav2_costmap_2d::InflationLayer::matchSize(), dwb_critics::PathDistCritic::prepare(), nav2_costmap_2d::StaticLayer::processMap(), nav2_costmap_2d::Costmap2DPublisher::publishCostmap(), dwb_core::DWBLocalPlanner::transformGlobalPlan(), nav2_smac_planner::CostmapDownsampler::updateCostmapSize(), and nav2_navfn_planner::NavfnPlanner::worldToMap().

| unsigned int nav2_costmap_2d::Costmap2D::getSizeInCellsX | ( | ) | const |
Accessor for the x size of the costmap in cells.
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().

| unsigned int nav2_costmap_2d::Costmap2D::getSizeInCellsY | ( | ) | const |
Accessor for the y size of the costmap in cells.
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().

| double nav2_costmap_2d::Costmap2D::getSizeInMetersX | ( | ) | const |
Accessor for the x size of the costmap in meters.
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().

| double nav2_costmap_2d::Costmap2D::getSizeInMetersY | ( | ) | const |
Accessor for the y size of the costmap in meters.
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().

|
inline |
Given an index... compute the associated map coordinates.
| index | The index |
| mx | Will be set to the x coordinate |
| my | Will be set to the y coordinate |
Definition at line 222 of file costmap_2d.hpp.
|
protectedvirtual |
Initializes the costmap, static_map, and markers data structures.
| size_x | The x size to use for map initialization |
| size_y | The y size to use for map initialization |
Definition at line 101 of file costmap_2d.cpp.
Referenced by copyCostmapWindow(), Costmap2D(), operator=(), and resizeMap().

| void nav2_costmap_2d::Costmap2D::mapToWorld | ( | unsigned int | mx, |
| unsigned int | my, | ||
| double & | wx, | ||
| double & | wy | ||
| ) | const |
Convert from map coordinates to world coordinates.
| mx | The x map coordinate |
| my | The y map coordinate |
| wx | Will be set to the associated world x coordinate |
| wy | Will 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(), nav2_costmap_2d::KeepoutFilter::updateBounds(), and nav2_costmap_2d::StaticLayer::updateCosts().

Overloaded assignment operator.
| map | The costmap to copy |
Definition at line 210 of file costmap_2d.cpp.
References deleteMaps(), and initMaps().

| 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.
| polygon | The polygon in map coordinates to rasterize |
| polygon_cells | Will 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().


|
inlineprotected |
Raytrace a line and apply some action at each step.
| at | The action to take... a functor |
| x0 | The starting x coordinate |
| y0 | The starting y coordinate |
| x1 | The ending x coordinate |
| y1 | The ending y coordinate |
| max_length | The maximum desired length of the segment... allows you to not go all the way to the endpoint |
| min_length | The minimum desired length of the segment |
Definition at line 430 of file costmap_2d.hpp.
Referenced by polygonOutlineCells(), and nav2_costmap_2d::ObstacleLayer::raytraceFreespace().

| bool nav2_costmap_2d::Costmap2D::saveMap | ( | std::string | file_name | ) |
Save the costmap out to a pgm file.
| file_name | The name of the file to save |
Definition at line 536 of file costmap_2d.cpp.
References getCost().

| 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.
| polygon | The polygon to perform the operation on |
| cost_value | The value to set costs to |
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().


| void nav2_costmap_2d::Costmap2D::setCost | ( | unsigned int | mx, |
| unsigned int | my, | ||
| unsigned char | cost | ||
| ) |
Set the cost of a cell in the costmap.
| mx | The x coordinate of the cell |
| my | The y coordinate of the cell |
| cost | The 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().


|
inline |
Set the default background value of the costmap.
| c | default value |
Definition at line 280 of file costmap_2d.hpp.
Referenced by nav2_costmap_2d::LayeredCostmap::LayeredCostmap().

|
virtual |
Move the origin of the costmap to a new location.... keeping data when it can.
| new_origin_x | The x coordinate of the new origin |
| new_origin_y | The 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().


| bool nav2_costmap_2d::Costmap2D::worldToMap | ( | double | wx, |
| double | wy, | ||
| unsigned int & | mx, | ||
| unsigned int & | my | ||
| ) | const |
Convert from world coordinates to map coordinates.
| wx | The x world coordinate |
| wy | The y world coordinate |
| mx | Will be set to the associated map x coordinate |
| my | Will be set to the associated map y coordinate |
Definition at line 287 of file costmap_2d.cpp.
Referenced by copyCostmapWindow(), nav2_navfn_planner::NavfnPlanner::createPlan(), nav2_smac_planner::SmacPlanner2D::createPlan(), nav2_smac_planner::SmacPlannerHybrid::createPlan(), nav2_smac_planner::SmacPlannerLattice::createPlan(), nav2_smac_planner::Smoother::findBoundaryExpansion(), nav2_costmap_2d::LayeredCostmap::isOutofBounds(), nav2_planner::PlannerServer::isPathValid(), dwb_critics::PathDistCritic::prepare(), nav2_costmap_2d::ObstacleLayer::raytraceFreespace(), dwb_critics::BaseObstacleCritic::scorePose(), dwb_critics::MapGridCritic::scorePose(), dwb_critics::ObstacleFootprintCritic::scorePose(), setConvexPolygonCost(), nav2_smac_planner::Smoother::smoothImpl(), nav2_smoother::SimpleSmoother::smoothImpl(), nav2_costmap_2d::ObstacleLayer::updateBounds(), and nav2_costmap_2d::StaticLayer::updateCosts().

| 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.
| wx | The x world coordinate |
| wy | The y world coordinate |
| mx | Will be set to the associated map x coordinate |
| my | Will be set to the associated map y coordinate |
Definition at line 308 of file costmap_2d.cpp.
Referenced by nav2_costmap_2d::LayeredCostmap::updateMap().

| 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.
| wx | The x world coordinate |
| wy | The y world coordinate |
| mx | Will be set to the associated map x coordinate |
| my | Will be set to the associated map y coordinate |
Definition at line 302 of file costmap_2d.cpp.
Referenced by nav2_costmap_2d::KeepoutFilter::process().
