Public Member Functions | Private Attributes | Friends | List of all members
ergodic_exploration::GridMap Class Reference

Constructs an 2D grid. More...

#include <grid.hpp>

Public Member Functions

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 GridDatagridData () 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...
 

Private Attributes

GridData grid_data_
 
double resolution_
 
double xmax_
 
double xmin_
 
unsigned int xsize_
 
double ymax_
 
double ymin_
 
unsigned int ysize_
 

Friends

class OccupancyMapper
 

Detailed Description

Constructs an 2D grid.

Definition at line 79 of file grid.hpp.

Constructor & Destructor Documentation

◆ GridMap() [1/3]

ergodic_exploration::GridMap::GridMap ( double  xmin,
double  xmax,
double  ymin,
double  ymax,
double  resolution,
const GridData grid_data 
)

Constructor.

Parameters
xmin- x low bound of grid
xmax- x upper bound of grid
ymin- y low bound of grid
ymax- y upper bound of grid
resolution- grid resolution
grid_ptr- shared pointer to current grid data

Definition at line 46 of file grid.cpp.

◆ GridMap() [2/3]

ergodic_exploration::GridMap::GridMap ( const nav_msgs::OccupancyGrid::ConstPtr &  grid_msg)

Constructor.

Parameters
grid_msg- ROS occupancy grid message

Definition at line 63 of file grid.cpp.

◆ GridMap() [3/3]

ergodic_exploration::GridMap::GridMap ( )

Constructor a empty grid.

Definition at line 79 of file grid.cpp.

Member Function Documentation

◆ getCell() [1/3]

double ergodic_exploration::GridMap::getCell ( double  x,
double  y 
) const

Get the value of the cell at a specified position.

Parameters
x- position in world (jth column)
y- position in world (ith row)
Returns
value of the cell

Definition at line 167 of file grid.cpp.

◆ getCell() [2/3]

double ergodic_exploration::GridMap::getCell ( unsigned int  i,
unsigned int  j 
) const

Get the value of the cell at a specified index.

Parameters
i- row in the grid (y-coordinate)
j- column in the grid (x-coordinate)
Returns
value of the cell

Definition at line 172 of file grid.cpp.

◆ getCell() [3/3]

double ergodic_exploration::GridMap::getCell ( unsigned int  idx) const

Get the value of the cell at a specified index.

Parameters
idx- row major index
Returns
value of the cell

Definition at line 177 of file grid.cpp.

◆ grid2RowMajor()

unsigned int ergodic_exploration::GridMap::grid2RowMajor ( unsigned int  i,
unsigned int  j 
) const

Converts grid indices to row major order index.

Parameters
i- row in the grid (y-coordinate)
j- column in the grid (x-coordinate)
Returns
grid index in row major order

Definition at line 109 of file grid.cpp.

◆ grid2World() [1/2]

std::vector< double > ergodic_exploration::GridMap::grid2World ( unsigned int  i,
unsigned int  j 
) const

Convert grid coordinates to world position.

Parameters
i- row in the grid (y-coordinate)
j- column in the grid (x-coordinate)
Returns
the x and y coordinates in the world

Definition at line 126 of file grid.cpp.

◆ grid2World() [2/2]

std::vector< double > ergodic_exploration::GridMap::grid2World ( unsigned int  idx) const

Convert row major index to world position.

Parameters
idx- row major index
Returns
the x and y coordinates in the world

Definition at line 133 of file grid.cpp.

◆ gridBounds() [1/2]

bool ergodic_exploration::GridMap::gridBounds ( unsigned int  i,
unsigned int  j 
) const

Test if coordinates are within the grid.

Parameters
i- row in the grid (y-coordinate)
j- column in the grid (x-coordinate)
Returns
true if coordinates are within the grid

Definition at line 96 of file grid.cpp.

◆ gridBounds() [2/2]

bool ergodic_exploration::GridMap::gridBounds ( unsigned int  idx) const

Test if coordinates are within the grid.

Parameters
idx- row major index
Returns
true if index is within the grid

Definition at line 102 of file grid.cpp.

◆ gridData()

const GridData& ergodic_exploration::GridMap::gridData ( ) const
inline

Return the grid data

Definition at line 202 of file grid.hpp.

◆ print()

void ergodic_exploration::GridMap::print ( ) const

Print grid properties.

Definition at line 186 of file grid.cpp.

◆ resolution()

double ergodic_exploration::GridMap::resolution ( ) const
inline

Return grid resolution.

Definition at line 208 of file grid.hpp.

◆ rowMajor2Grid()

std::vector< unsigned int > ergodic_exploration::GridMap::rowMajor2Grid ( unsigned int  idx) const

Convert row major index to row and column indices.

Parameters
idx- row major index
Returns
row and column indices

Definition at line 119 of file grid.cpp.

◆ size()

unsigned int ergodic_exploration::GridMap::size ( ) const
inline

Return grid size.

Definition at line 250 of file grid.hpp.

◆ update()

void ergodic_exploration::GridMap::update ( const nav_msgs::OccupancyGrid::ConstPtr &  grid_msg)

Update the grid.

Parameters
grid_msg- ROS occupancy grid message

Definition at line 84 of file grid.cpp.

◆ world2Grid()

std::vector< unsigned int > ergodic_exploration::GridMap::world2Grid ( double  x,
double  y 
) const

Convert world coordinates to row and column index in grid.

Parameters
x- position in world (jth column)
y- position in world (ith row)
Returns
ith row and jth column in grid

Definition at line 143 of file grid.cpp.

◆ world2RowMajor()

unsigned int ergodic_exploration::GridMap::world2RowMajor ( double  x,
double  y 
) const

Convert world coordinates to row major index.

Parameters
x- position in world (jth column)
y- position in world (ith row)
Returns
row major index

Definition at line 161 of file grid.cpp.

◆ xmax()

double ergodic_exploration::GridMap::xmax ( ) const
inline

Return grid xmax.

Definition at line 226 of file grid.hpp.

◆ xmin()

double ergodic_exploration::GridMap::xmin ( ) const
inline

Return grid xmin.

Definition at line 214 of file grid.hpp.

◆ xsize()

unsigned int ergodic_exploration::GridMap::xsize ( ) const
inline

Return grid x-axis size.

Definition at line 238 of file grid.hpp.

◆ ymax()

double ergodic_exploration::GridMap::ymax ( ) const
inline

Return grid ymax.

Definition at line 232 of file grid.hpp.

◆ ymin()

double ergodic_exploration::GridMap::ymin ( ) const
inline

Return grid ymin.

Definition at line 220 of file grid.hpp.

◆ ysize()

unsigned int ergodic_exploration::GridMap::ysize ( ) const
inline

Return y-axis size.

Definition at line 244 of file grid.hpp.

Friends And Related Function Documentation

◆ OccupancyMapper

friend class OccupancyMapper
friend

Definition at line 82 of file grid.hpp.

Member Data Documentation

◆ grid_data_

GridData ergodic_exploration::GridMap::grid_data_
private

Definition at line 258 of file grid.hpp.

◆ resolution_

double ergodic_exploration::GridMap::resolution_
private

Definition at line 257 of file grid.hpp.

◆ xmax_

double ergodic_exploration::GridMap::xmax_
private

Definition at line 257 of file grid.hpp.

◆ xmin_

double ergodic_exploration::GridMap::xmin_
private

Definition at line 257 of file grid.hpp.

◆ xsize_

unsigned int ergodic_exploration::GridMap::xsize_
private

Definition at line 256 of file grid.hpp.

◆ ymax_

double ergodic_exploration::GridMap::ymax_
private

Definition at line 257 of file grid.hpp.

◆ ymin_

double ergodic_exploration::GridMap::ymin_
private

Definition at line 257 of file grid.hpp.

◆ ysize_

unsigned int ergodic_exploration::GridMap::ysize_
private

Definition at line 256 of file grid.hpp.


The documentation for this class was generated from the following files:


ergodic_exploration
Author(s): bostoncleek
autogenerated on Wed Mar 2 2022 00:17:13