|
double | getCell (double x, double y) const |
| Get the value of the cell at a specified position. More...
|
|
double | getCell (unsigned int i, unsigned int j) const |
| Get the value of the cell at a specified index. More...
|
|
double | getCell (unsigned int idx) const |
| Get the value of the cell at a specified index. More...
|
|
unsigned int | grid2RowMajor (unsigned int i, unsigned int j) const |
| Converts grid indices to row major order index. More...
|
|
std::vector< double > | grid2World (unsigned int i, unsigned int j) const |
| Convert grid coordinates to world position. More...
|
|
std::vector< double > | grid2World (unsigned int idx) const |
| Convert row major index to world position. More...
|
|
bool | gridBounds (unsigned int i, unsigned int j) const |
| Test if coordinates are within the grid. More...
|
|
bool | gridBounds (unsigned int idx) const |
| Test if coordinates are within the grid. More...
|
|
const GridData & | gridData () const |
| Return the grid data
More...
|
|
| GridMap () |
| Constructor a empty grid. More...
|
|
| GridMap (const nav_msgs::OccupancyGrid::ConstPtr &grid_msg) |
| Constructor. More...
|
|
| GridMap (double xmin, double xmax, double ymin, double ymax, double resolution, const GridData &grid_data) |
| Constructor. More...
|
|
void | print () const |
| Print grid properties. More...
|
|
double | resolution () const |
| Return grid resolution. More...
|
|
std::vector< unsigned int > | rowMajor2Grid (unsigned int idx) const |
| Convert row major index to row and column indices. More...
|
|
unsigned int | size () const |
| Return grid size. More...
|
|
void | update (const nav_msgs::OccupancyGrid::ConstPtr &grid_msg) |
| Update the grid. More...
|
|
std::vector< unsigned int > | world2Grid (double x, double y) const |
| Convert world coordinates to row and column index in grid. More...
|
|
unsigned int | world2RowMajor (double x, double y) const |
| Convert world coordinates to row major index. More...
|
|
double | xmax () const |
| Return grid xmax. More...
|
|
double | xmin () const |
| Return grid xmin. More...
|
|
unsigned int | xsize () const |
| Return grid x-axis size. More...
|
|
double | ymax () const |
| Return grid ymax. More...
|
|
double | ymin () const |
| Return grid ymin. More...
|
|
unsigned int | ysize () const |
| Return y-axis size. More...
|
|
Constructs an 2D grid.
Definition at line 79 of file grid.hpp.