An occupancy grid implementation. More...
#include <grid_map.h>
Public Types | |
using | Cell = std::shared_ptr< GridCell > |
Public Member Functions | |
double | cell_scale () const |
Returnes the scale. More... | |
double | cell_value (const DiscretePoint2D &cell_coord) const |
const std::vector< std::vector< Cell > > | cells () const |
Returns map's cells. More... | |
GridMap (std::shared_ptr< GridCellFactory > cell_factory, const GridMapParams &init_params) | |
int | height () const |
Returns thr height of the map. More... | |
int | map_center_x () const |
int | map_center_y () const |
double | scale () const |
Returns the scale. More... | |
void | update_cell (const DiscretePoint2D &cell_coord, const Occupancy &new_value, double quality=1.0) |
int | width () const |
Returns the width of the map. More... | |
Rectangle | world_cell_bounds (const DiscretePoint2D &cell_coord) |
DiscretePoint2D | world_to_cell (double x, double y) const |
Private Types | |
using | Map = std::vector< Row > |
using | Row = std::vector< Cell > |
Private Member Functions | |
void | add_cols (const int cols_count, std::function< Row::iterator(Row &)> it) |
void | add_rows (const int rows_count, Map::iterator it) |
int | calc_sufficient_bound (const int container_coord, const int map_bound) |
long | closest_bounded_power_two (long x) |
bool | has_cell (const DiscretePoint2D &cell_coord) const |
void | resize_bound (const int dim, const int container_coord) |
void | resize_in_direction (const int delta, const int direction_flag) |
void | update_size (const DiscretePoint2D &cell_coord) |
Private Attributes | |
std::shared_ptr< GridCellFactory > | _cell_factory |
Map | _cells |
int | _height |
double | _m_per_cell |
int | _map_center_x |
int | _map_center_y |
Cell | _unvisited_cell |
int | _width |
const int | RESIZE_BWD = 1 |
const int | RESIZE_DIM_BIT = 1 |
const int | RESIZE_DIR_BIT = 0 |
const int | RESIZE_DOWN = RESIZE_DIR(RESIZE_VERT, RESIZE_BWD) |
const int | RESIZE_FWD = 0 |
const int | RESIZE_HORZ = 1 |
const int | RESIZE_LEFT = RESIZE_DIR(RESIZE_HORZ, RESIZE_BWD) |
const int | RESIZE_RIGHT = RESIZE_DIR(RESIZE_HORZ, RESIZE_FWD) |
const int | RESIZE_UP = RESIZE_DIR(RESIZE_VERT, RESIZE_FWD) |
const int | RESIZE_VERT = 0 |
An occupancy grid implementation.
Definition at line 22 of file grid_map.h.
using GridMap::Cell = std::shared_ptr<GridCell> |
Definition at line 24 of file grid_map.h.
|
private |
Definition at line 27 of file grid_map.h.
|
private |
Definition at line 26 of file grid_map.h.
|
inline |
Creates a GridCell based map.
cell_factory | The factory that creates a requied type of Cell. |
Definition at line 35 of file grid_map.h.
|
inlineprivate |
Definition at line 213 of file grid_map.h.
|
inlineprivate |
Definition at line 202 of file grid_map.h.
|
inlineprivate |
Definition at line 164 of file grid_map.h.
|
inline |
Returnes the scale.
Definition at line 110 of file grid_map.h.
|
inline |
Returns the probability of the cell to be occupied.
cell_coord | A point with coordinates of requied cell in Grid Map. |
Definition at line 90 of file grid_map.h.
|
inline |
Returns map's cells.
Definition at line 63 of file grid_map.h.
|
inlineprivate |
Definition at line 177 of file grid_map.h.
|
inlineprivate |
Definition at line 136 of file grid_map.h.
|
inline |
Returns thr height of the map.
Definition at line 57 of file grid_map.h.
|
inline |
Returns the coordinate of the map center
Definition at line 129 of file grid_map.h.
|
inline |
Returns the coordinate of the map center
Definition at line 133 of file grid_map.h.
|
inlineprivate |
Definition at line 149 of file grid_map.h.
|
inlineprivate |
Definition at line 185 of file grid_map.h.
|
inline |
Returns the scale.
Definition at line 60 of file grid_map.h.
|
inline |
Updates a cell with a new occupancy data.
cell_coord | Coordinates of a cell. |
new_value | The probability for cell of being occupied. |
quality | The Measure of beleif to the data. |
Definition at line 76 of file grid_map.h.
|
inlineprivate |
Definition at line 141 of file grid_map.h.
|
inline |
Returns the width of the map.
Definition at line 54 of file grid_map.h.
|
inline |
Returns the bounds of the cell in the World.
cell_coord | The point with coordinates of requied cell in the grid map. |
Definition at line 117 of file grid_map.h.
|
inline |
Projects coordinates in meters onto a cell of the grid map.
Definition at line 101 of file grid_map.h.
|
private |
Definition at line 248 of file grid_map.h.
|
private |
Definition at line 249 of file grid_map.h.
|
private |
Definition at line 244 of file grid_map.h.
|
private |
Definition at line 246 of file grid_map.h.
|
private |
Definition at line 245 of file grid_map.h.
|
private |
Definition at line 245 of file grid_map.h.
|
private |
Definition at line 247 of file grid_map.h.
|
private |
Definition at line 244 of file grid_map.h.
|
private |
Definition at line 234 of file grid_map.h.
|
private |
Definition at line 231 of file grid_map.h.
|
private |
Definition at line 235 of file grid_map.h.
|
private |
Definition at line 238 of file grid_map.h.
|
private |
Definition at line 233 of file grid_map.h.
|
private |
Definition at line 230 of file grid_map.h.
|
private |
Definition at line 240 of file grid_map.h.
|
private |
Definition at line 239 of file grid_map.h.
|
private |
Definition at line 237 of file grid_map.h.
|
private |
Definition at line 229 of file grid_map.h.