A DynamicVoronoi object computes and updates a distance map and Voronoi diagram. More...
#include <dynamicvoronoi.h>
Classes | |
| struct | dataCell |
Public Member Functions | |
| void | clearCell (int x, int y) |
| remove an obstacle at the specified cell coordinate | |
| DynamicVoronoi () | |
| void | exchangeObstacles (std::vector< INTPOINT > newObstacles) |
| remove old dynamic obstacles and add the new ones | |
| float | getDistance (int x, int y) |
| returns the obstacle distance at the specified location | |
| unsigned int | getSizeX () |
| returns the horizontal size of the workspace/map | |
| unsigned int | getSizeY () |
| returns the vertical size of the workspace/map | |
| void | initializeEmpty (int _sizeX, int _sizeY, bool initGridMap=true) |
| Initialization with an empty map. | |
| void | initializeMap (int _sizeX, int _sizeY, bool **_gridMap) |
| Initialization with a given binary map (false==free, true==occupied) | |
| bool | isOccupied (int x, int y) |
| checks whether the specficied location is occupied | |
| bool | isVoronoi (int x, int y) |
| returns whether the specified cell is part of the (pruned) Voronoi graph | |
| void | occupyCell (int x, int y) |
| add an obstacle at the specified cell coordinate | |
| void | prune () |
| prune the Voronoi diagram | |
| void | update (bool updateRealDist=true) |
| update distance map and Voronoi diagram to reflect the changes | |
| void | visualize (const char *filename="result.ppm") |
| write the current distance map and voronoi diagram as ppm file | |
| ~DynamicVoronoi () | |
Private Types | |
| enum | markerMatchResult { pruned, keep, retry } |
| enum | ObstDataState { invalidObstData = SHRT_MAX/2 } |
| enum | QueueingState { fwNotQueued = 1, fwQueued = 2, fwProcessed = 3, bwQueued = 4, bwProcessed = 1 } |
| enum | State { voronoiKeep = -4, freeQueued = -3, voronoiRetry = -2, voronoiPrune = -1, free = 0, occupied = 1 } |
Private Member Functions | |
| void | checkVoro (int x, int y, int nx, int ny, dataCell &c, dataCell &nc) |
| void | commitAndColorize (bool updateRealDist=true) |
| bool | isOccupied (int &x, int &y, dataCell &c) |
| markerMatchResult | markerMatch (int x, int y) |
| void | recheckVoro () |
| void | removeObstacle (int x, int y) |
| void | reviveVoroNeighbors (int &x, int &y) |
| void | setObstacle (int x, int y) |
Private Attributes | |
| std::vector< INTPOINT > | addList |
| dataCell ** | data |
| double | doubleThreshold |
| bool ** | gridMap |
| std::vector< INTPOINT > | lastObstacles |
| BucketPrioQueue | open |
| int | padding |
| std::queue< INTPOINT > | pruneQueue |
| std::vector< INTPOINT > | removeList |
| int | sizeX |
| int | sizeY |
| double | sqrt2 |
A DynamicVoronoi object computes and updates a distance map and Voronoi diagram.
Definition at line 13 of file dynamicvoronoi.h.
enum DynamicVoronoi::markerMatchResult [private] |
Definition at line 65 of file dynamicvoronoi.h.
enum DynamicVoronoi::ObstDataState [private] |
Definition at line 64 of file dynamicvoronoi.h.
enum DynamicVoronoi::QueueingState [private] |
Definition at line 63 of file dynamicvoronoi.h.
enum DynamicVoronoi::State [private] |
Definition at line 62 of file dynamicvoronoi.h.
| void DynamicVoronoi::checkVoro | ( | int | x, |
| int | y, | ||
| int | nx, | ||
| int | ny, | ||
| dataCell & | c, | ||
| dataCell & | nc | ||
| ) | [inline, private] |
| void DynamicVoronoi::clearCell | ( | int | x, |
| int | y | ||
| ) |
remove an obstacle at the specified cell coordinate
| void DynamicVoronoi::commitAndColorize | ( | bool | updateRealDist = true | ) | [private] |
| void DynamicVoronoi::exchangeObstacles | ( | std::vector< INTPOINT > | newObstacles | ) |
remove old dynamic obstacles and add the new ones
| float DynamicVoronoi::getDistance | ( | int | x, |
| int | y | ||
| ) |
returns the obstacle distance at the specified location
| unsigned int DynamicVoronoi::getSizeX | ( | ) | [inline] |
returns the horizontal size of the workspace/map
Definition at line 47 of file dynamicvoronoi.h.
| unsigned int DynamicVoronoi::getSizeY | ( | ) | [inline] |
returns the vertical size of the workspace/map
Definition at line 49 of file dynamicvoronoi.h.
| void DynamicVoronoi::initializeEmpty | ( | int | _sizeX, |
| int | _sizeY, | ||
| bool | initGridMap = true |
||
| ) |
Initialization with an empty map.
| void DynamicVoronoi::initializeMap | ( | int | _sizeX, |
| int | _sizeY, | ||
| bool ** | _gridMap | ||
| ) |
Initialization with a given binary map (false==free, true==occupied)
| bool DynamicVoronoi::isOccupied | ( | int | x, |
| int | y | ||
| ) |
checks whether the specficied location is occupied
| bool DynamicVoronoi::isOccupied | ( | int & | x, |
| int & | y, | ||
| dataCell & | c | ||
| ) | [inline, private] |
| bool DynamicVoronoi::isVoronoi | ( | int | x, |
| int | y | ||
| ) |
returns whether the specified cell is part of the (pruned) Voronoi graph
| markerMatchResult DynamicVoronoi::markerMatch | ( | int | x, |
| int | y | ||
| ) | [inline, private] |
| void DynamicVoronoi::occupyCell | ( | int | x, |
| int | y | ||
| ) |
add an obstacle at the specified cell coordinate
| void DynamicVoronoi::prune | ( | ) |
prune the Voronoi diagram
| void DynamicVoronoi::recheckVoro | ( | ) | [private] |
| void DynamicVoronoi::removeObstacle | ( | int | x, |
| int | y | ||
| ) | [private] |
| void DynamicVoronoi::reviveVoroNeighbors | ( | int & | x, |
| int & | y | ||
| ) | [inline, private] |
| void DynamicVoronoi::setObstacle | ( | int | x, |
| int | y | ||
| ) | [private] |
| void DynamicVoronoi::update | ( | bool | updateRealDist = true | ) |
update distance map and Voronoi diagram to reflect the changes
| void DynamicVoronoi::visualize | ( | const char * | filename = "result.ppm" | ) |
write the current distance map and voronoi diagram as ppm file
std::vector<INTPOINT> DynamicVoronoi::addList [private] |
Definition at line 86 of file dynamicvoronoi.h.
dataCell** DynamicVoronoi::data [private] |
Definition at line 92 of file dynamicvoronoi.h.
double DynamicVoronoi::doubleThreshold [private] |
Definition at line 97 of file dynamicvoronoi.h.
bool** DynamicVoronoi::gridMap [private] |
Definition at line 93 of file dynamicvoronoi.h.
std::vector<INTPOINT> DynamicVoronoi::lastObstacles [private] |
Definition at line 87 of file dynamicvoronoi.h.
BucketPrioQueue DynamicVoronoi::open [private] |
Definition at line 82 of file dynamicvoronoi.h.
int DynamicVoronoi::padding [private] |
Definition at line 96 of file dynamicvoronoi.h.
std::queue<INTPOINT> DynamicVoronoi::pruneQueue [private] |
Definition at line 83 of file dynamicvoronoi.h.
std::vector<INTPOINT> DynamicVoronoi::removeList [private] |
Definition at line 85 of file dynamicvoronoi.h.
int DynamicVoronoi::sizeX [private] |
Definition at line 91 of file dynamicvoronoi.h.
int DynamicVoronoi::sizeY [private] |
Definition at line 90 of file dynamicvoronoi.h.
double DynamicVoronoi::sqrt2 [private] |
Definition at line 99 of file dynamicvoronoi.h.