#include <GridMap.h>
|
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) |
|
Definition at line 7 of file GridMap.h.
bool GridMap::getCoordinates |
( |
unsigned int & |
x, |
|
|
unsigned int & |
y, |
|
|
unsigned int |
i |
|
) |
| |
|
inline |
signed char GridMap::getData |
( |
unsigned int |
index | ) |
|
|
inline |
signed char GridMap::getData |
( |
int |
x, |
|
|
int |
y |
|
) |
| |
|
inline |
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 |
bool GridMap::getIndex |
( |
unsigned int |
x, |
|
|
unsigned int |
y, |
|
|
unsigned int & |
i |
|
) |
| |
|
inline |
signed char GridMap::getLethalCost |
( |
| ) |
|
|
inline |
const nav_msgs::OccupancyGrid& GridMap::getMap |
( |
| ) |
const |
|
inline |
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 |
double GridMap::getOriginY |
( |
| ) |
|
|
inline |
double GridMap::getResolution |
( |
| ) |
|
|
inline |
unsigned int GridMap::getSize |
( |
| ) |
|
|
inline |
unsigned int GridMap::getWidth |
( |
| ) |
|
|
inline |
bool GridMap::isFree |
( |
unsigned int |
index | ) |
|
|
inline |
bool GridMap::isFree |
( |
int |
x, |
|
|
int |
y |
|
) |
| |
|
inline |
bool GridMap::isFrontier |
( |
unsigned int |
index | ) |
|
|
inline |
bool GridMap::setData |
( |
unsigned int |
index, |
|
|
signed char |
value |
|
) |
| |
|
inline |
bool GridMap::setData |
( |
int |
x, |
|
|
int |
y, |
|
|
signed char |
value |
|
) |
| |
|
inline |
void GridMap::setLethalCost |
( |
signed char |
c | ) |
|
|
inline |
void GridMap::update |
( |
nav_msgs::OccupancyGrid |
grid | ) |
|
|
inline |
signed char GridMap::mLethalCost |
|
private |
unsigned int GridMap::mMapHeight |
|
private |
unsigned int GridMap::mMapWidth |
|
private |
nav_msgs::OccupancyGrid GridMap::mOccupancyGrid |
|
private |
The documentation for this class was generated from the following file: