Public Member Functions | Static Public Member Functions | Public Attributes | Private Attributes | List of all members
base_local_planner::MapGrid Class Reference

A grid of MapCell cells that is used to propagate path and goal distances for the trajectory controller. More...

#include <map_grid.h>

Public Member Functions

void commonInit ()
 Utility to share initialization code across constructors. More...
 
void computeGoalDistance (std::queue< MapCell * > &dist_queue, const costmap_2d::Costmap2D &costmap)
 Compute the distance from each cell in the local map grid to the local goal point. More...
 
void computeTargetDistance (std::queue< MapCell * > &dist_queue, const costmap_2d::Costmap2D &costmap)
 Compute the distance from each cell in the local map grid to the planned path. More...
 
MapCellgetCell (unsigned int x, unsigned int y)
 
size_t getIndex (int x, int y)
 Returns a 1D index into the MapCell array for a 2D index. More...
 
 MapGrid ()
 Creates a 0x0 map by default. More...
 
 MapGrid (unsigned int size_x, unsigned int size_y)
 Creates a map of size_x by size_y. More...
 
 MapGrid (const MapGrid &mg)
 Copy constructor for a MapGrid. More...
 
double obstacleCosts ()
 
MapCelloperator() (unsigned int x, unsigned int y)
 Returns a map cell accessed by (col, row) More...
 
MapCell operator() (unsigned int x, unsigned int y) const
 Returns a map cell accessed by (col, row) More...
 
MapGridoperator= (const MapGrid &mg)
 Assignment operator for a MapGrid. More...
 
void resetPathDist ()
 reset path distance fields for all cells More...
 
void setLocalGoal (const costmap_2d::Costmap2D &costmap, const std::vector< geometry_msgs::PoseStamped > &global_plan)
 Update what cell is considered the next local goal. More...
 
void setTargetCells (const costmap_2d::Costmap2D &costmap, const std::vector< geometry_msgs::PoseStamped > &global_plan)
 Update what cells are considered path based on the global plan. More...
 
void sizeCheck (unsigned int size_x, unsigned int size_y)
 check if we need to resize More...
 
double unreachableCellCosts ()
 
bool updatePathCell (MapCell *current_cell, MapCell *check_cell, const costmap_2d::Costmap2D &costmap)
 Used to update the distance of a cell in path distance computation. More...
 
 ~MapGrid ()
 Destructor for a MapGrid. More...
 

Static Public Member Functions

static void adjustPlanResolution (const std::vector< geometry_msgs::PoseStamped > &global_plan_in, std::vector< geometry_msgs::PoseStamped > &global_plan_out, double resolution)
 

Public Attributes

double goal_x_
 
double goal_y_
 The goal distance was last computed from. More...
 
unsigned int size_x_
 
unsigned int size_y_
 The dimensions of the grid. More...
 

Private Attributes

std::vector< MapCellmap_
 Storage for the MapCells. More...
 

Detailed Description

A grid of MapCell cells that is used to propagate path and goal distances for the trajectory controller.

Definition at line 52 of file map_grid.h.

Constructor & Destructor Documentation

base_local_planner::MapGrid::MapGrid ( )

Creates a 0x0 map by default.

Definition at line 40 of file map_grid.cpp.

base_local_planner::MapGrid::MapGrid ( unsigned int  size_x,
unsigned int  size_y 
)

Creates a map of size_x by size_y.

Parameters
size_xThe width of the map
size_yThe height of the map

Definition at line 45 of file map_grid.cpp.

base_local_planner::MapGrid::~MapGrid ( )
inline

Destructor for a MapGrid.

Definition at line 94 of file map_grid.h.

base_local_planner::MapGrid::MapGrid ( const MapGrid mg)

Copy constructor for a MapGrid.

Parameters
mgThe MapGrid to copy

Definition at line 51 of file map_grid.cpp.

Member Function Documentation

void base_local_planner::MapGrid::adjustPlanResolution ( const std::vector< geometry_msgs::PoseStamped > &  global_plan_in,
std::vector< geometry_msgs::PoseStamped > &  global_plan_out,
double  resolution 
)
static

increase global plan resolution to match that of the costmap by adding points linearly between global plan points This is necessary where global planners produce plans with few points.

Parameters
global_plan_ininput
global_plan_outputoutput
resolutiondesired distance between waypoints

Definition at line 133 of file map_grid.cpp.

void base_local_planner::MapGrid::commonInit ( )

Utility to share initialization code across constructors.

Definition at line 57 of file map_grid.cpp.

void base_local_planner::MapGrid::computeGoalDistance ( std::queue< MapCell * > &  dist_queue,
const costmap_2d::Costmap2D costmap 
)

Compute the distance from each cell in the local map grid to the local goal point.

Parameters
goal_queueA queue containing the local goal cell
void base_local_planner::MapGrid::computeTargetDistance ( std::queue< MapCell * > &  dist_queue,
const costmap_2d::Costmap2D costmap 
)

Compute the distance from each cell in the local map grid to the planned path.

Parameters
dist_queueA queue of the initial cells on the path

Definition at line 255 of file map_grid.cpp.

MapCell& base_local_planner::MapGrid::getCell ( unsigned int  x,
unsigned int  y 
)
inline

Definition at line 87 of file map_grid.h.

size_t base_local_planner::MapGrid::getIndex ( int  x,
int  y 
)

Returns a 1D index into the MapCell array for a 2D index.

Parameters
xThe desired x coordinate
yThe desired y coordinate
Returns
The associated 1D index

Definition at line 73 of file map_grid.cpp.

double base_local_planner::MapGrid::obstacleCosts ( )
inline

return a value that indicates cell is in obstacle

Definition at line 136 of file map_grid.h.

MapCell& base_local_planner::MapGrid::operator() ( unsigned int  x,
unsigned int  y 
)
inline

Returns a map cell accessed by (col, row)

Parameters
xThe x coordinate of the cell
yThe y coordinate of the cell
Returns
A reference to the desired cell

Definition at line 73 of file map_grid.h.

MapCell base_local_planner::MapGrid::operator() ( unsigned int  x,
unsigned int  y 
) const
inline

Returns a map cell accessed by (col, row)

Parameters
xThe x coordinate of the cell
yThe y coordinate of the cell
Returns
A copy of the desired cell

Definition at line 83 of file map_grid.h.

MapGrid & base_local_planner::MapGrid::operator= ( const MapGrid mg)

Assignment operator for a MapGrid.

Parameters
mgThe MapGrid to assign from

Definition at line 77 of file map_grid.cpp.

void base_local_planner::MapGrid::resetPathDist ( )

reset path distance fields for all cells

Definition at line 125 of file map_grid.cpp.

void base_local_planner::MapGrid::setLocalGoal ( const costmap_2d::Costmap2D costmap,
const std::vector< geometry_msgs::PoseStamped > &  global_plan 
)

Update what cell is considered the next local goal.

Definition at line 210 of file map_grid.cpp.

void base_local_planner::MapGrid::setTargetCells ( const costmap_2d::Costmap2D costmap,
const std::vector< geometry_msgs::PoseStamped > &  global_plan 
)

Update what cells are considered path based on the global plan.

Definition at line 171 of file map_grid.cpp.

void base_local_planner::MapGrid::sizeCheck ( unsigned int  size_x,
unsigned int  size_y 
)

check if we need to resize

Parameters
size_xThe desired width
size_yThe desired height

Definition at line 84 of file map_grid.cpp.

double base_local_planner::MapGrid::unreachableCellCosts ( )
inline

returns a value indicating cell was not reached by wavefront propagation of set cells. (is behind walls, regarding the region covered by grid)

Definition at line 144 of file map_grid.h.

bool base_local_planner::MapGrid::updatePathCell ( MapCell current_cell,
MapCell check_cell,
const costmap_2d::Costmap2D costmap 
)
inline

Used to update the distance of a cell in path distance computation.

Parameters
current_cellThe cell we're currently in
check_cellThe cell to be updated

Definition at line 103 of file map_grid.cpp.

Member Data Documentation

double base_local_planner::MapGrid::goal_x_

Definition at line 189 of file map_grid.h.

double base_local_planner::MapGrid::goal_y_

The goal distance was last computed from.

Definition at line 189 of file map_grid.h.

std::vector<MapCell> base_local_planner::MapGrid::map_
private

Storage for the MapCells.

Definition at line 195 of file map_grid.h.

unsigned int base_local_planner::MapGrid::size_x_

Definition at line 191 of file map_grid.h.

unsigned int base_local_planner::MapGrid::size_y_

The dimensions of the grid.

Definition at line 191 of file map_grid.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 Thu Jan 21 2021 04:05:49