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. | |
| 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. | |
| void | computePathDistance (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. | |
| MapCell & | getCell (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. | |
| MapGrid (const MapGrid &mg) | |
| Copy constructor for a MapGrid. | |
| MapGrid (unsigned int size_x, unsigned int size_y, double scale, double x, double y) | |
| Creates a map of size_x by size_y with the desired scale and origin. | |
| MapGrid (unsigned int size_x, unsigned int size_y) | |
| Creates a map of size_x by size_y. | |
| MapGrid () | |
| Creates a 0x0 map by default. | |
| MapCell | operator() (unsigned int x, unsigned int y) const |
| Returns a map cell accessed by (col, row). | |
| MapCell & | operator() (unsigned int x, unsigned int y) |
| Returns a map cell accessed by (col, row). | |
| MapGrid & | operator= (const MapGrid &mg) |
| Assignment operator for a MapGrid. | |
| void | resetPathDist () |
| reset path distance fields for all cells | |
| void | setPathCells (const costmap_2d::Costmap2D &costmap, const std::vector< geometry_msgs::PoseStamped > &global_plan) |
| Update what cells are considered path based on the global plan. | |
| void | sizeCheck (unsigned int size_x, unsigned int size_y, double o_x, double o_y) |
| check if we need to resize | |
| void | updateGoalCell (MapCell *current_cell, MapCell *check_cell, std::queue< MapCell * > &dist_queue, const costmap_2d::Costmap2D &costmap) |
| Used to update the distance of a cell in goal distance computation. | |
| void | updatePathCell (MapCell *current_cell, MapCell *check_cell, std::queue< MapCell * > &dist_queue, const costmap_2d::Costmap2D &costmap) |
| Used to update the distance of a cell in path distance computation. | |
| ~MapGrid () | |
| Destructor for a MapGrid. | |
Public Attributes | |
| double | goal_x_ |
| double | goal_y_ |
| The goal distance was last computed from. | |
| std::vector< MapCell > | map_ |
| Storage for the MapCells. | |
| double | origin_x |
| double | origin_y |
| lower left corner of grid in world space | |
| double | scale |
| grid scale in meters/cell | |
| unsigned int | size_x_ |
| unsigned int | size_y_ |
| The dimensions of the grid. | |
A grid of MapCell cells that is used to propagate path and goal distances for the trajectory controller.
Definition at line 49 of file map_grid.h.
| 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.
| size_x | The width of the map | |
| size_y | The height of the map |
Definition at line 45 of file map_grid.cpp.
| base_local_planner::MapGrid::MapGrid | ( | unsigned int | size_x, | |
| unsigned int | size_y, | |||
| double | scale, | |||
| double | x, | |||
| double | y | |||
| ) |
Creates a map of size_x by size_y with the desired scale and origin.
| size_x | The width of the map | |
| size_y | The height of the map | |
| scale | The resolution of each MapCell | |
| x | The x coordinate of the origin of the map | |
| y | The y coordinate of the origin of the map |
Definition at line 51 of file map_grid.cpp.
| base_local_planner::MapGrid::~MapGrid | ( | ) | [inline] |
Destructor for a MapGrid.
Definition at line 100 of file map_grid.h.
| base_local_planner::MapGrid::MapGrid | ( | const MapGrid & | mg | ) |
Copy constructor for a MapGrid.
| mg | The MapGrid to copy |
Definition at line 57 of file map_grid.cpp.
| void base_local_planner::MapGrid::commonInit | ( | ) |
Utility to share initialization code across constructors.
Definition at line 63 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.
| goal_queue | A queue containing the local goal cell |
| void base_local_planner::MapGrid::computePathDistance | ( | 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.
| dist_queue | A queue of the initial cells on the path |
| MapCell& base_local_planner::MapGrid::getCell | ( | unsigned int | x, | |
| unsigned int | y | |||
| ) | [inline] |
Definition at line 93 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.
| x | The desired x coordinate | |
| y | The desired y coordinate |
Definition at line 79 of file map_grid.cpp.
| MapCell base_local_planner::MapGrid::operator() | ( | unsigned int | x, | |
| unsigned int | y | |||
| ) | const [inline] |
Returns a map cell accessed by (col, row).
| x | The x coordinate of the cell | |
| y | The y coordinate of the cell |
Definition at line 89 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).
| x | The x coordinate of the cell | |
| y | The y coordinate of the cell |
Definition at line 79 of file map_grid.h.
Assignment operator for a MapGrid.
| mg | The MapGrid to assign from |
Definition at line 83 of file map_grid.cpp.
| void base_local_planner::MapGrid::resetPathDist | ( | ) |
reset path distance fields for all cells
Definition at line 111 of file map_grid.cpp.
| void base_local_planner::MapGrid::setPathCells | ( | 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 122 of file map_grid.cpp.
| void base_local_planner::MapGrid::sizeCheck | ( | unsigned int | size_x, | |
| unsigned int | size_y, | |||
| double | o_x, | |||
| double | o_y | |||
| ) |
check if we need to resize
| size_x | The desired width | |
| size_y | The desired height | |
| o_x | the desired x coordinate of the origin | |
| o_y | the desired y coordinate of the origin |
Definition at line 90 of file map_grid.cpp.
| void base_local_planner::MapGrid::updateGoalCell | ( | MapCell * | current_cell, | |
| MapCell * | check_cell, | |||
| std::queue< MapCell * > & | dist_queue, | |||
| const costmap_2d::Costmap2D & | costmap | |||
| ) | [inline] |
Used to update the distance of a cell in goal distance computation.
| current_cell | The cell we're currently in | |
| check_cell | The cell to be updated |
mark the cell as visited
Definition at line 170 of file map_grid.h.
| void base_local_planner::MapGrid::updatePathCell | ( | MapCell * | current_cell, | |
| MapCell * | check_cell, | |||
| std::queue< MapCell * > & | dist_queue, | |||
| const costmap_2d::Costmap2D & | costmap | |||
| ) | [inline] |
Used to update the distance of a cell in path distance computation.
| current_cell | The cell we're currently in | |
| check_cell | The cell to be updated |
Definition at line 146 of file map_grid.h.
Definition at line 211 of file map_grid.h.
The goal distance was last computed from.
Definition at line 211 of file map_grid.h.
| std::vector<MapCell> base_local_planner::MapGrid::map_ |
Storage for the MapCells.
Definition at line 207 of file map_grid.h.
Definition at line 213 of file map_grid.h.
lower left corner of grid in world space
Definition at line 213 of file map_grid.h.
grid scale in meters/cell
Definition at line 209 of file map_grid.h.
| unsigned int base_local_planner::MapGrid::size_x_ |
Definition at line 206 of file map_grid.h.
| unsigned int base_local_planner::MapGrid::size_y_ |
The dimensions of the grid.
Definition at line 206 of file map_grid.h.