#include <OcTree.h>
Public Types | |
typedef spatialaggregate::OcTreeNodeFixedCountAllocator < float, ValueClass > | Allocator |
typedef boost::shared_ptr < Allocator > | AllocatorPtr |
typedef std::vector< PointIndices > | NodeIdToPointIdxVector |
typedef std::list< NodePtr > | NodePointerList |
typedef std::vector< NodePtr > | NodePointers |
typedef spatialaggregate::OcTreeNode < float, ValueClass > * | NodePtr |
typedef spatialaggregate::OcTree < float, ValueClass > | Octree |
typedef spatialaggregate::OcTreeKey < float, ValueClass > | OctreeKey |
typedef Octree * | OctreePtr |
typedef std::vector< int > | PointIndices |
typedef algorithm::OcTreeSamplingMap < float, ValueClass > | SamplingMap |
typedef NormalEstimationValueClass | ValueClass |
typedef Eigen::Vector3f | Vec3 |
Public Member Functions | |
template<typename PointCloudType > | |
void | buildOctree (const PointCloudType &pointCloud) |
bool | checkGetAllLeafs () const |
bool | checkOctreeNodes (const NodePointers &nodePointers) const |
bool | checkSamplingMap () const |
void | findFinestNormal (Vec3 &normal, const Vec3 &point) const |
void | getAllLeafs (NodePointers &leafNodes, const NodePtr &topNode) const |
float | getCellSizeFromDepth (const unsigned int &depth) const |
const unsigned int & | getMaxDepth () const |
void | getNeighboringNodes (NodePointers &neighborNodes, const NodePtr &node, const unsigned int &maxSearchDepth, const float &neighborhoodSize=1.f) const |
void | getNeighboringNodes (NodePointers &neighborNodes, const NodePtr &currNode, const unsigned int &maxSearchDepth, const unsigned int &currDepth, const OctreeKey &minPos, const OctreeKey &maxPos) const |
const NodePointerList & | getNodeListOnDepth (const unsigned int &depth) const |
NodePointers | getNodesOnDepth (const unsigned int &depth) const |
const OctreePtr & | getOctreePtr () const |
const PointIndices & | getPointsFromNodeId (const unsigned int &nodeId) const |
const PointIndices & | getPointsFromNodePtr (const NodePtr &nodePtr) const |
const SamplingMap & | getSamplingMap () const |
OcTree (float minOctreeResolution, float rho_max, float principalVarFactor, float minPointsForNormal, float curvThreshold, float curv2Threshold, float sqDistFactor, size_t numPoints) | |
void | preAllocate (const size_t &numPoints) |
~OcTree () | |
Private Attributes | |
AllocatorPtr | mAllocatorPtr |
float | mCurv2Threshold |
float | mCurvThreshold |
float | mMinOctreeResolution |
float | mMinPointsForNormal |
NodeIdToPointIdxVector | mNodeIdToPointIdxVector |
unsigned int | mOctreeDepth |
OctreePtr | mOctreePtr |
float | mPrincipalVarFactor |
float | mRho_max |
SamplingMap | mSamplingMap |
float | mSqDistFactor |
typedef spatialaggregate::OcTreeNodeFixedCountAllocator<float, ValueClass> OcTree::Allocator |
typedef boost::shared_ptr<Allocator> OcTree::AllocatorPtr |
typedef std::vector<PointIndices> OcTree::NodeIdToPointIdxVector |
typedef std::list<NodePtr> OcTree::NodePointerList |
typedef std::vector<NodePtr> OcTree::NodePointers |
typedef spatialaggregate::OcTreeNode<float, ValueClass>* OcTree::NodePtr |
typedef spatialaggregate::OcTree<float, ValueClass> OcTree::Octree |
typedef spatialaggregate::OcTreeKey<float, ValueClass> OcTree::OctreeKey |
typedef Octree* OcTree::OctreePtr |
typedef std::vector<int> OcTree::PointIndices |
typedef algorithm::OcTreeSamplingMap<float, ValueClass> OcTree::SamplingMap |
typedef Eigen::Vector3f OcTree::Vec3 |
OcTree::OcTree | ( | float | minOctreeResolution, |
float | rho_max, | ||
float | principalVarFactor, | ||
float | minPointsForNormal, | ||
float | curvThreshold, | ||
float | curv2Threshold, | ||
float | sqDistFactor, | ||
size_t | numPoints | ||
) | [inline] |
OcTree::~OcTree | ( | ) | [inline] |
void OcTree::buildOctree | ( | const PointCloudType & | pointCloud | ) |
bool OcTree::checkGetAllLeafs | ( | ) | const [inline] |
bool OcTree::checkOctreeNodes | ( | const NodePointers & | nodePointers | ) | const [inline] |
bool OcTree::checkSamplingMap | ( | ) | const [inline] |
void OcTree::findFinestNormal | ( | Vec3 & | normal, |
const Vec3 & | point | ||
) | const [inline] |
void OcTree::getAllLeafs | ( | NodePointers & | leafNodes, |
const NodePtr & | topNode | ||
) | const [inline] |
float OcTree::getCellSizeFromDepth | ( | const unsigned int & | depth | ) | const [inline] |
const unsigned int& OcTree::getMaxDepth | ( | ) | const [inline] |
void OcTree::getNeighboringNodes | ( | NodePointers & | neighborNodes, |
const NodePtr & | node, | ||
const unsigned int & | maxSearchDepth, | ||
const float & | neighborhoodSize = 1.f |
||
) | const [inline] |
void OcTree::getNeighboringNodes | ( | NodePointers & | neighborNodes, |
const NodePtr & | currNode, | ||
const unsigned int & | maxSearchDepth, | ||
const unsigned int & | currDepth, | ||
const OctreeKey & | minPos, | ||
const OctreeKey & | maxPos | ||
) | const [inline] |
const NodePointerList& OcTree::getNodeListOnDepth | ( | const unsigned int & | depth | ) | const [inline] |
NodePointers OcTree::getNodesOnDepth | ( | const unsigned int & | depth | ) | const [inline] |
const OctreePtr& OcTree::getOctreePtr | ( | ) | const [inline] |
const PointIndices& OcTree::getPointsFromNodeId | ( | const unsigned int & | nodeId | ) | const [inline] |
const PointIndices& OcTree::getPointsFromNodePtr | ( | const NodePtr & | nodePtr | ) | const [inline] |
const SamplingMap& OcTree::getSamplingMap | ( | ) | const [inline] |
void OcTree::preAllocate | ( | const size_t & | numPoints | ) | [inline] |
AllocatorPtr OcTree::mAllocatorPtr [private] |
float OcTree::mCurv2Threshold [private] |
float OcTree::mCurvThreshold [private] |
float OcTree::mMinOctreeResolution [private] |
float OcTree::mMinPointsForNormal [private] |
unsigned int OcTree::mOctreeDepth [private] |
OctreePtr OcTree::mOctreePtr [private] |
float OcTree::mPrincipalVarFactor [private] |
float OcTree::mRho_max [private] |
SamplingMap OcTree::mSamplingMap [private] |
float OcTree::mSqDistFactor [private] |