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

#include <GridMap.h>

Public Member Functions

bool getCoordinates (unsigned int &x, unsigned int &y, unsigned int i)
 
signed char getData (unsigned int index)
 
signed char getData (int x, int y)
 
std::vector< unsigned int > getFreeNeighbors (unsigned int index, int offset=1)
 
unsigned int getHeight ()
 
bool getIndex (unsigned int x, unsigned int y, unsigned int &i)
 
signed char getLethalCost ()
 
const nav_msgs::OccupancyGrid & getMap () const
 
std::vector< unsigned int > getNeighbors (unsigned int index, bool diagonal=false)
 
double getOriginX ()
 
double getOriginY ()
 
double getResolution ()
 
unsigned int getSize ()
 
unsigned int getWidth ()
 
bool isFree (unsigned int index)
 
bool isFree (int x, int y)
 
bool isFrontier (unsigned int index)
 
bool setData (unsigned int index, signed char value)
 
bool setData (int x, int y, signed char value)
 
void setLethalCost (signed char c)
 
void update (nav_msgs::OccupancyGrid grid)
 

Private Attributes

signed char mLethalCost
 
unsigned int mMapHeight
 
unsigned int mMapWidth
 
nav_msgs::OccupancyGrid mOccupancyGrid
 

Detailed Description

Definition at line 7 of file GridMap.h.

Member Function Documentation

bool GridMap::getCoordinates ( unsigned int &  x,
unsigned int &  y,
unsigned int  i 
)
inline

Definition at line 42 of file GridMap.h.

signed char GridMap::getData ( unsigned int  index)
inline

Definition at line 55 of file GridMap.h.

signed char GridMap::getData ( int  x,
int  y 
)
inline

Definition at line 138 of file GridMap.h.

std::vector<unsigned int> GridMap::getFreeNeighbors ( unsigned int  index,
int  offset = 1 
)
inline

Gets indices of all free neighboring cells with given offset

Definition at line 98 of file GridMap.h.

unsigned int GridMap::getHeight ( )
inline

Definition at line 19 of file GridMap.h.

bool GridMap::getIndex ( unsigned int  x,
unsigned int  y,
unsigned int &  i 
)
inline

Definition at line 31 of file GridMap.h.

signed char GridMap::getLethalCost ( )
inline

Definition at line 25 of file GridMap.h.

const nav_msgs::OccupancyGrid& GridMap::getMap ( ) const
inline

Definition at line 28 of file GridMap.h.

std::vector<unsigned int> GridMap::getNeighbors ( unsigned int  index,
bool  diagonal = false 
)
inline

Gets indices of all neighboring cells

Definition at line 115 of file GridMap.h.

double GridMap::getOriginX ( )
inline

Definition at line 22 of file GridMap.h.

double GridMap::getOriginY ( )
inline

Definition at line 23 of file GridMap.h.

double GridMap::getResolution ( )
inline

Definition at line 21 of file GridMap.h.

unsigned int GridMap::getSize ( )
inline

Definition at line 20 of file GridMap.h.

unsigned int GridMap::getWidth ( )
inline

Definition at line 18 of file GridMap.h.

bool GridMap::isFree ( unsigned int  index)
inline

Definition at line 73 of file GridMap.h.

bool GridMap::isFree ( int  x,
int  y 
)
inline

Definition at line 156 of file GridMap.h.

bool GridMap::isFrontier ( unsigned int  index)
inline

Definition at line 80 of file GridMap.h.

bool GridMap::setData ( unsigned int  index,
signed char  value 
)
inline

Definition at line 63 of file GridMap.h.

bool GridMap::setData ( int  x,
int  y,
signed char  value 
)
inline

Definition at line 146 of file GridMap.h.

void GridMap::setLethalCost ( signed char  c)
inline

Definition at line 26 of file GridMap.h.

void GridMap::update ( nav_msgs::OccupancyGrid  grid)
inline

Definition at line 10 of file GridMap.h.

Member Data Documentation

signed char GridMap::mLethalCost
private

Definition at line 167 of file GridMap.h.

unsigned int GridMap::mMapHeight
private

Definition at line 166 of file GridMap.h.

unsigned int GridMap::mMapWidth
private

Definition at line 165 of file GridMap.h.

nav_msgs::OccupancyGrid GridMap::mOccupancyGrid
private

Definition at line 164 of file GridMap.h.


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


nav2d_navigator
Author(s): Sebastian Kasperski
autogenerated on Tue Nov 7 2017 06:02:48