#include <GridMap.h>
Public Types | |
typedef NodeGridCell | Cell |
typedef std::vector< int > | NodeIndices |
typedef OcTree::NodePointers | NodePointers |
typedef std::vector< NodePointers > | NodePointersVec |
typedef std::vector< int > | PointIndices |
typedef std::vector< unsigned int > | uints |
Public Member Functions | |
void | blindPopulate (Vec3 pos) |
template<typename PointCloudType > | |
void | blindPopulate (const PointIndices &pointIndices, const PointCloudType &pointCloud) |
void | calculateStartPos () |
void | checkNodesAgainstGridConnection (NodeIndices &outNodeIndices, const NodePointers &inNodeCandidates, float newCellSize, unsigned int minNodesCount) const |
bool | checkPointConnection (const Vec3 &p, const int &connectionNeighbors) const |
void | clear () |
void | clearIndices () |
void | gatherNodesInCC (NodePointers &outputNodes, const ConnectedComponent &conComp, const NodePointers &octreeNodes) const |
void | gatherNodesInCC (NodeIndices &outputIndices, const ConnectedComponent &conComp) const |
void | getConnectedComponentsAndNotConnectedNodes (NodePointersVec &nodesInCC, const NodePointers &inputOctreeNodes, float cellSize, unsigned int minPlaneNodes, unsigned int minCCNodes, NodePointers *notConnectedNodesOutput=NULL) |
void | getNewExtremes (float &xMinOut, float &xMaxOut, float &yMinOut, float &yMaxOut, unsigned int &xOff, unsigned int &xAdd, unsigned int &yOff, unsigned int &yAdd, float xMinIn, float xMaxIn, float yMinIn, float yMaxIn, float stepsize) const |
const Indices & | getStartPos () const |
GridMap () | |
GridMap (const Plane3D &plane, float xMin, float xMax, float yMin, float yMax, float cellSize) | |
GridMap (const GridMap &gridMap, float xMin, float xMax, float yMin, float yMax, unsigned int xOff, unsigned int xAdd, unsigned int yOff, unsigned int yAdd, float cellSize) | |
bool | isPopulated (Vec3 pos) |
void | populate (const unsigned int &index, Vec3 pos) |
template<typename PointCloudType > | |
void | populate (const PointIndices &pointIndices, const PointCloudType &pointCloud) |
void | populate (const NodePointers &nodePointers) |
void | print () const |
void | print (const std::pair< unsigned int, unsigned int > &coords) const |
void | pushPopulatedUnvisitedNeighbors (std::queue< std::pair< unsigned int, unsigned int > > &neighbors, const unsigned int &width, const unsigned int &height) const |
void | startConnectedComponentAt (ConnectedComponent &ccc, const Indices &startPos) |
Protected Attributes | |
Indices | mGridCCStartPos |
typedef NodeGridCell GridMap::Cell |
typedef std::vector<int> GridMap::NodeIndices |
typedef std::vector<NodePointers> GridMap::NodePointersVec |
typedef std::vector<int> GridMap::PointIndices |
typedef std::vector<unsigned int> GridMap::uints |
GridMap::GridMap | ( | ) | [inline] |
GridMap::GridMap | ( | const Plane3D & | plane, |
float | xMin, | ||
float | xMax, | ||
float | yMin, | ||
float | yMax, | ||
float | cellSize | ||
) | [inline] |
GridMap::GridMap | ( | const GridMap & | gridMap, |
float | xMin, | ||
float | xMax, | ||
float | yMin, | ||
float | yMax, | ||
unsigned int | xOff, | ||
unsigned int | xAdd, | ||
unsigned int | yOff, | ||
unsigned int | yAdd, | ||
float | cellSize | ||
) |
Definition at line 41 of file GridMap.cpp.
void GridMap::blindPopulate | ( | Vec3 | pos | ) | [inline] |
void GridMap::blindPopulate | ( | const PointIndices & | pointIndices, |
const PointCloudType & | pointCloud | ||
) |
void GridMap::calculateStartPos | ( | ) |
Definition at line 331 of file GridMap.cpp.
void GridMap::checkNodesAgainstGridConnection | ( | NodeIndices & | outNodeIndices, |
const NodePointers & | inNodeCandidates, | ||
float | newCellSize, | ||
unsigned int | minNodesCount | ||
) | const |
Definition at line 199 of file GridMap.cpp.
bool GridMap::checkPointConnection | ( | const Vec3 & | p, |
const int & | connectionNeighbors | ||
) | const [inline] |
void GridMap::clear | ( | ) | [inline] |
void GridMap::clearIndices | ( | ) | [inline] |
void GridMap::gatherNodesInCC | ( | NodePointers & | outputNodes, |
const ConnectedComponent & | conComp, | ||
const NodePointers & | octreeNodes | ||
) | const |
Definition at line 231 of file GridMap.cpp.
void GridMap::gatherNodesInCC | ( | NodeIndices & | outputIndices, |
const ConnectedComponent & | conComp | ||
) | const |
Definition at line 244 of file GridMap.cpp.
void GridMap::getConnectedComponentsAndNotConnectedNodes | ( | NodePointersVec & | nodesInCC, |
const NodePointers & | inputOctreeNodes, | ||
float | cellSize, | ||
unsigned int | minPlaneNodes, | ||
unsigned int | minCCNodes, | ||
NodePointers * | notConnectedNodesOutput = NULL |
||
) |
Definition at line 256 of file GridMap.cpp.
void GridMap::getNewExtremes | ( | float & | xMinOut, |
float & | xMaxOut, | ||
float & | yMinOut, | ||
float & | yMaxOut, | ||
unsigned int & | xOff, | ||
unsigned int & | xAdd, | ||
unsigned int & | yOff, | ||
unsigned int & | yAdd, | ||
float | xMinIn, | ||
float | xMaxIn, | ||
float | yMinIn, | ||
float | yMaxIn, | ||
float | stepsize | ||
) | const |
Definition at line 294 of file GridMap.cpp.
const Indices& GridMap::getStartPos | ( | ) | const [inline] |
bool GridMap::isPopulated | ( | Vec3 | pos | ) | [inline] |
void GridMap::populate | ( | const unsigned int & | index, |
Vec3 | pos | ||
) | [inline] |
void GridMap::populate | ( | const PointIndices & | pointIndices, |
const PointCloudType & | pointCloud | ||
) |
void GridMap::populate | ( | const NodePointers & | nodePointers | ) | [inline] |
void GridMap::print | ( | ) | const |
Definition at line 142 of file GridMap.cpp.
void GridMap::print | ( | const std::pair< unsigned int, unsigned int > & | coords | ) | const |
Definition at line 154 of file GridMap.cpp.
void GridMap::pushPopulatedUnvisitedNeighbors | ( | std::queue< std::pair< unsigned int, unsigned int > > & | neighbors, |
const unsigned int & | width, | ||
const unsigned int & | height | ||
) | const |
Definition at line 86 of file GridMap.cpp.
void GridMap::startConnectedComponentAt | ( | ConnectedComponent & | ccc, |
const Indices & | startPos | ||
) |
Definition at line 174 of file GridMap.cpp.
Indices GridMap::mGridCCStartPos [protected] |