Public Types | Public Member Functions | Private Attributes
OcTree Class Reference

#include <OcTree.h>

List of all members.

Public Types

typedef
spatialaggregate::OcTreeNodeFixedCountAllocator
< float, ValueClass
Allocator
typedef boost::shared_ptr
< Allocator
AllocatorPtr
typedef std::vector< PointIndicesNodeIdToPointIdxVector
typedef std::list< NodePtrNodePointerList
typedef std::vector< NodePtrNodePointers
typedef
spatialaggregate::OcTreeNode
< float, ValueClass > * 
NodePtr
typedef
spatialaggregate::OcTree
< float, ValueClass
Octree
typedef
spatialaggregate::OcTreeKey
< float, ValueClass
OctreeKey
typedef OctreeOctreePtr
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 NodePointerListgetNodeListOnDepth (const unsigned int &depth) const
NodePointers getNodesOnDepth (const unsigned int &depth) const
const OctreePtrgetOctreePtr () const
const PointIndicesgetPointsFromNodeId (const unsigned int &nodeId) const
const PointIndicesgetPointsFromNodePtr (const NodePtr &nodePtr) const
const SamplingMapgetSamplingMap () 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

Detailed Description

Definition at line 46 of file OcTree.h.


Member Typedef Documentation

typedef spatialaggregate::OcTreeNodeFixedCountAllocator<float, ValueClass> OcTree::Allocator

Definition at line 51 of file OcTree.h.

typedef boost::shared_ptr<Allocator> OcTree::AllocatorPtr

Definition at line 52 of file OcTree.h.

Definition at line 59 of file OcTree.h.

typedef std::list<NodePtr> OcTree::NodePointerList

Definition at line 57 of file OcTree.h.

typedef std::vector<NodePtr> OcTree::NodePointers

Definition at line 56 of file OcTree.h.

typedef spatialaggregate::OcTreeNode<float, ValueClass>* OcTree::NodePtr

Definition at line 54 of file OcTree.h.

typedef spatialaggregate::OcTree<float, ValueClass> OcTree::Octree

Definition at line 49 of file OcTree.h.

typedef spatialaggregate::OcTreeKey<float, ValueClass> OcTree::OctreeKey

Definition at line 55 of file OcTree.h.

Definition at line 50 of file OcTree.h.

typedef std::vector<int> OcTree::PointIndices

Definition at line 58 of file OcTree.h.

typedef algorithm::OcTreeSamplingMap<float, ValueClass> OcTree::SamplingMap

Definition at line 53 of file OcTree.h.

Definition at line 48 of file OcTree.h.

typedef Eigen::Vector3f OcTree::Vec3

Definition at line 60 of file OcTree.h.


Constructor & Destructor Documentation

OcTree::OcTree ( float  minOctreeResolution,
float  rho_max,
float  principalVarFactor,
float  minPointsForNormal,
float  curvThreshold,
float  curv2Threshold,
float  sqDistFactor,
size_t  numPoints 
) [inline]

Definition at line 62 of file OcTree.h.

OcTree::~OcTree ( ) [inline]

Definition at line 70 of file OcTree.h.


Member Function Documentation

template<typename PointCloudType >
void OcTree::buildOctree ( const PointCloudType &  pointCloud)

Definition at line 193 of file OcTree.h.

bool OcTree::checkGetAllLeafs ( ) const [inline]

Definition at line 94 of file OcTree.h.

bool OcTree::checkOctreeNodes ( const NodePointers nodePointers) const [inline]

Definition at line 101 of file OcTree.h.

bool OcTree::checkSamplingMap ( ) const [inline]

Definition at line 80 of file OcTree.h.

void OcTree::findFinestNormal ( Vec3 normal,
const Vec3 point 
) const [inline]

Definition at line 156 of file OcTree.h.

void OcTree::getAllLeafs ( NodePointers leafNodes,
const NodePtr topNode 
) const [inline]

Definition at line 299 of file OcTree.h.

float OcTree::getCellSizeFromDepth ( const unsigned int &  depth) const [inline]

Definition at line 152 of file OcTree.h.

const unsigned int& OcTree::getMaxDepth ( ) const [inline]

Definition at line 113 of file OcTree.h.

void OcTree::getNeighboringNodes ( NodePointers neighborNodes,
const NodePtr node,
const unsigned int &  maxSearchDepth,
const float &  neighborhoodSize = 1.f 
) const [inline]

Definition at line 265 of file OcTree.h.

void OcTree::getNeighboringNodes ( NodePointers neighborNodes,
const NodePtr currNode,
const unsigned int &  maxSearchDepth,
const unsigned int &  currDepth,
const OctreeKey minPos,
const OctreeKey maxPos 
) const [inline]

Definition at line 282 of file OcTree.h.

const NodePointerList& OcTree::getNodeListOnDepth ( const unsigned int &  depth) const [inline]

Definition at line 121 of file OcTree.h.

NodePointers OcTree::getNodesOnDepth ( const unsigned int &  depth) const [inline]

Definition at line 126 of file OcTree.h.

const OctreePtr& OcTree::getOctreePtr ( ) const [inline]

Definition at line 137 of file OcTree.h.

const PointIndices& OcTree::getPointsFromNodeId ( const unsigned int &  nodeId) const [inline]

Definition at line 142 of file OcTree.h.

const PointIndices& OcTree::getPointsFromNodePtr ( const NodePtr nodePtr) const [inline]

Definition at line 147 of file OcTree.h.

const SamplingMap& OcTree::getSamplingMap ( ) const [inline]

Definition at line 117 of file OcTree.h.

void OcTree::preAllocate ( const size_t &  numPoints) [inline]

Definition at line 188 of file OcTree.h.


Member Data Documentation

Definition at line 172 of file OcTree.h.

float OcTree::mCurv2Threshold [private]

Definition at line 184 of file OcTree.h.

float OcTree::mCurvThreshold [private]

Definition at line 183 of file OcTree.h.

Definition at line 179 of file OcTree.h.

float OcTree::mMinPointsForNormal [private]

Definition at line 182 of file OcTree.h.

Definition at line 176 of file OcTree.h.

unsigned int OcTree::mOctreeDepth [private]

Definition at line 174 of file OcTree.h.

Definition at line 173 of file OcTree.h.

float OcTree::mPrincipalVarFactor [private]

Definition at line 181 of file OcTree.h.

float OcTree::mRho_max [private]

Definition at line 180 of file OcTree.h.

Definition at line 175 of file OcTree.h.

float OcTree::mSqDistFactor [private]

Definition at line 185 of file OcTree.h.


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


structure_coloring_fkie
Author(s): Bastian Gaspers
autogenerated on Sun Jan 5 2014 11:38:09