#include <multi_grid_octree_data.h>
Classes | |
class | AdjacencyCountFunction |
class | AdjacencySetFunction |
class | DivergenceFunction |
class | FaceEdgesFunction |
class | LaplacianMatrixFunction |
class | LaplacianProjectionFunction |
class | PointIndexValueAndNormalFunction |
class | PointIndexValueFunction |
class | RefineFunction |
class | RestrictedLaplacianMatrixFunction |
Public Member Functions | |
void | ClipTree (void) |
void | finalize1 (const int &refineNeighbors=-1) |
void | finalize2 (const int &refineNeighbors=-1) |
Real | GetIsoValue (void) |
void | GetMCIsoTriangles (const Real &isoValue, CoredMeshData *mesh, const int &fullDepthIso=0, const int &nonLinearFit=1, bool addBarycenter=false, bool polygonMesh=false) |
void | GetMCIsoTriangles (const Real &isoValue, const int &subdivideDepth, CoredMeshData *mesh, const int &fullDepthIso=0, const int &nonLinearFit=1, bool addBarycenter=false, bool polygonMesh=false) |
int | LaplacianMatrixIteration (const int &subdivideDepth) |
Octree () | |
void | setFunctionData (const PPolynomial< Degree > &ReconstructionFunction, const int &maxDepth, const int &normalize, const Real &normalSmooth=-1) |
void | SetLaplacianWeights (void) |
template<typename PointNT > | |
int | setTree (boost::shared_ptr< const pcl::PointCloud< PointNT > > input_, const int &maxDepth, const int &kernelDepth, const Real &samplesPerNode, const Real &scaleFactor, Point3D< Real > ¢er, Real &scale, const int &resetSamples, const int &useConfidence) |
Static Public Member Functions | |
static double | MemoryUsage () |
Public Attributes | |
FunctionData< Degree, FunctionDataReal > | fData |
std::vector< Point3D< Real > > * | normals |
Real | postNormalSmooth |
TreeOctNode | tree |
Static Public Attributes | |
static double | maxMemoryUsage = 0 |
Private Member Functions | |
Real | getCenterValue (const TreeOctNode *node) |
Real | getCornerValue (const TreeOctNode *node, const int &corner) |
void | getCornerValueAndNormal (const TreeOctNode *node, const int &corner, Real &value, Point3D< Real > &normal) |
Real | GetDivergence (const int index[DIMENSION], const Point3D< Real > &normal) const |
Real | GetDotProduct (const int index[DIMENSION]) const |
int | GetFixedDepthLaplacian (SparseSymmetricMatrix< float > &matrix, const int &depth, const SortedTreeNodes &sNodes) |
Real | GetLaplacian (const int index[DIMENSION]) const |
void | GetMCIsoEdges (TreeOctNode *node, hash_map< long long, int > &boundaryRoots, hash_map< long long, int > *interiorRoots, const int &sDepth, std::vector< std::pair< long long, long long > > &edges) |
int | GetMCIsoTriangles (TreeOctNode *node, CoredMeshData *mesh, hash_map< long long, int > &boundaryRoots, hash_map< long long, int > *interiorRoots, std::vector< Point3D< float > > *interiorPositions, const int &offSet, const int &sDepth, bool addBarycenter, bool polygonMesh) |
int | GetRestrictedFixedDepthLaplacian (SparseSymmetricMatrix< float > &matrix, const int &depth, const int *entries, const int &entryCount, const TreeOctNode *rNode, const Real &radius, const SortedTreeNodes &sNodes) |
int | GetRoot (const RootInfo &ri, const Real &isoValue, const int &maxDepth, Point3D< Real > &position, hash_map< long long, std::pair< Real, Point3D< Real > > > &normalHash, Point3D< Real > *normal, const int &nonLinearFit) |
int | GetRoot (const RootInfo &ri, const Real &isoValue, Point3D< Real > &position, hash_map< long long, std::pair< Real, Point3D< Real > > > &normalHash, const int &nonLinearFit) |
int | HasNormals (TreeOctNode *node, const Real &epsilon) |
void | NonLinearGetSampleDepthAndWeight (TreeOctNode *node, const Point3D< Real > &position, const Real &samplesPerNode, Real &depth, Real &weight) |
Real | NonLinearGetSampleWeight (TreeOctNode *node, const Point3D< Real > &position) |
int | NonLinearSplatOrientedPoint (TreeOctNode *node, const Point3D< Real > &point, const Point3D< Real > &normal) |
void | NonLinearSplatOrientedPoint (const Point3D< Real > &point, const Point3D< Real > &normal, const int &kernelDepth, const Real &samplesPerNode, const int &minDepth, const int &maxDepth) |
int | NonLinearUpdateWeightContribution (TreeOctNode *node, const Point3D< Real > &position, const Real &weight=Real(1.0)) |
void | PreValidate (const Real &isoValue, const int &maxDepth, const int &subdivideDepth) |
void | PreValidate (TreeOctNode *node, const Real &isoValue, const int &maxDepth, const int &subdivideDepth) |
int | SetBoundaryMCRootPositions (const int &sDepth, const Real &isoValue, hash_map< long long, int > &boundaryRoots, hash_map< long long, std::pair< Real, Point3D< Real > > > &boundaryNormalHash, CoredMeshData *mesh, const int &nonLinearFit) |
void | SetIsoSurfaceCorners (const Real &isoValue, const int &subdivisionDepth, const int &fullDepthIso) |
int | SetMCRootPositions (TreeOctNode *node, const int &sDepth, const Real &isoValue, hash_map< long long, int > &boundaryRoots, hash_map< long long, int > *interiorRoots, hash_map< long long, std::pair< Real, Point3D< Real > > > &boundaryNormalHash, hash_map< long long, std::pair< Real, Point3D< Real > > > *interiorNormalHash, std::vector< Point3D< float > > *interiorPositions, CoredMeshData *mesh, const int &nonLinearFit) |
void | setNodeIndices (TreeOctNode &tree, int &idx) |
int | SolveFixedDepthMatrix (const int &depth, const SortedTreeNodes &sNodes) |
int | SolveFixedDepthMatrix (const int &depth, const int &startingDepth, const SortedTreeNodes &sNodes) |
void | Subdivide (TreeOctNode *node, const Real &isoValue, const int &maxDepth) |
void | Validate (TreeOctNode *node, const Real &isoValue, const int &maxDepth, const int &fullDepthIso, const int &subdivideDepth) |
void | Validate (TreeOctNode *node, const Real &isoValue, const int &maxDepth, const int &fullDepthIso) |
Static Private Member Functions | |
static int | AddTriangles (CoredMeshData *mesh, std::vector< CoredPointIndex > edges[3], std::vector< Point3D< float > > *interiorPositions, const int &offSet) |
static int | AddTriangles (CoredMeshData *mesh, std::vector< CoredPointIndex > &edges, std::vector< Point3D< float > > *interiorPositions, const int &offSet, bool addBarycenter, bool polygonMesh) |
static int | EdgeRootCount (const TreeOctNode *node, const int &edgeIndex, const int &maxDepth) |
static int | GetEdgeLoops (std::vector< std::pair< long long, long long > > &edges, std::vector< std::vector< std::pair< long long, long long > > > &loops) |
static int | GetRootIndex (const TreeOctNode *node, const int &edgeIndex, const int &maxDepth, RootInfo &ri) |
static int | GetRootIndex (const TreeOctNode *node, const int &edgeIndex, const int &maxDepth, const int &sDepth, RootInfo &ri) |
static int | GetRootIndex (const long long &key, hash_map< long long, int > &boundaryRoots, hash_map< long long, int > *interiorRoots, CoredPointIndex &index) |
static int | GetRootPair (const RootInfo &root, const int &maxDepth, RootInfo &pair) |
static int | InteriorFaceRootCount (const TreeOctNode *node, const int &faceIndex, const int &maxDepth) |
static int | IsBoundaryEdge (const TreeOctNode *node, const int &edgeIndex, const int &subdivideDepth) |
static int | IsBoundaryEdge (const TreeOctNode *node, const int &dir, const int &x, const int &y, const int &subidivideDepth) |
static int | IsBoundaryFace (const TreeOctNode *node, const int &faceIndex, const int &subdivideDepth) |
Private Attributes | |
TreeOctNode::NeighborKey | neighborKey |
TreeOctNode::NeighborKey2 | neighborKey2 |
Real | radius |
int | width |
Definition at line 129 of file multi_grid_octree_data.h.
pcl::poisson::Octree< Degree >::Octree | ( | ) |
Definition at line 142 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::AddTriangles | ( | CoredMeshData * | mesh, |
std::vector< CoredPointIndex > | edges[3], | ||
std::vector< Point3D< float > > * | interiorPositions, | ||
const int & | offSet | ||
) | [static, private] |
Definition at line 3122 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::AddTriangles | ( | CoredMeshData * | mesh, |
std::vector< CoredPointIndex > & | edges, | ||
std::vector< Point3D< float > > * | interiorPositions, | ||
const int & | offSet, | ||
bool | addBarycenter, | ||
bool | polygonMesh | ||
) | [static, private] |
Definition at line 3137 of file multi_grid_octree_data.hpp.
void pcl::poisson::Octree< Degree >::ClipTree | ( | void | ) |
Definition at line 1124 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::EdgeRootCount | ( | const TreeOctNode * | node, |
const int & | edgeIndex, | ||
const int & | maxDepth | ||
) | [static, private] |
Definition at line 2057 of file multi_grid_octree_data.hpp.
void pcl::poisson::Octree< Degree >::finalize1 | ( | const int & | refineNeighbors = -1 | ) |
Definition at line 652 of file multi_grid_octree_data.hpp.
void pcl::poisson::Octree< Degree >::finalize2 | ( | const int & | refineNeighbors = -1 | ) |
Definition at line 685 of file multi_grid_octree_data.hpp.
Real pcl::poisson::Octree< Degree >::getCenterValue | ( | const TreeOctNode * | node | ) | [private] |
Definition at line 1507 of file multi_grid_octree_data.hpp.
Real pcl::poisson::Octree< Degree >::getCornerValue | ( | const TreeOctNode * | node, |
const int & | corner | ||
) | [private] |
Definition at line 1566 of file multi_grid_octree_data.hpp.
void pcl::poisson::Octree< Degree >::getCornerValueAndNormal | ( | const TreeOctNode * | node, |
const int & | corner, | ||
Real & | value, | ||
Point3D< Real > & | normal | ||
) | [private] |
Definition at line 1626 of file multi_grid_octree_data.hpp.
Real pcl::poisson::Octree< Degree >::GetDivergence | ( | const int | index[DIMENSION], |
const Point3D< Real > & | normal | ||
) | const [private] |
Definition at line 707 of file multi_grid_octree_data.hpp.
Real pcl::poisson::Octree< Degree >::GetDotProduct | ( | const int | index[DIMENSION] | ) | const [private] |
Definition at line 722 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::GetEdgeLoops | ( | std::vector< std::pair< long long, long long > > & | edges, |
std::vector< std::vector< std::pair< long long, long long > > > & | loops | ||
) | [static, private] |
Definition at line 3053 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::GetFixedDepthLaplacian | ( | SparseSymmetricMatrix< float > & | matrix, |
const int & | depth, | ||
const SortedTreeNodes & | sNodes | ||
) | [private] |
Definition at line 729 of file multi_grid_octree_data.hpp.
Real pcl::poisson::Octree< Degree >::GetIsoValue | ( | void | ) |
Definition at line 1692 of file multi_grid_octree_data.hpp.
Real pcl::poisson::Octree< Degree >::GetLaplacian | ( | const int | index[DIMENSION] | ) | const [private] |
Definition at line 715 of file multi_grid_octree_data.hpp.
void pcl::poisson::Octree< Degree >::GetMCIsoEdges | ( | TreeOctNode * | node, |
hash_map< long long, int > & | boundaryRoots, | ||
hash_map< long long, int > * | interiorRoots, | ||
const int & | sDepth, | ||
std::vector< std::pair< long long, long long > > & | edges | ||
) | [private] |
Definition at line 2913 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::GetMCIsoTriangles | ( | TreeOctNode * | node, |
CoredMeshData * | mesh, | ||
hash_map< long long, int > & | boundaryRoots, | ||
hash_map< long long, int > * | interiorRoots, | ||
std::vector< Point3D< float > > * | interiorPositions, | ||
const int & | offSet, | ||
const int & | sDepth, | ||
bool | addBarycenter, | ||
bool | polygonMesh | ||
) | [private] |
Definition at line 3022 of file multi_grid_octree_data.hpp.
void pcl::poisson::Octree< Degree >::GetMCIsoTriangles | ( | const Real & | isoValue, |
CoredMeshData * | mesh, | ||
const int & | fullDepthIso = 0 , |
||
const int & | nonLinearFit = 1 , |
||
bool | addBarycenter = false , |
||
bool | polygonMesh = false |
||
) |
Definition at line 1393 of file multi_grid_octree_data.hpp.
void pcl::poisson::Octree< Degree >::GetMCIsoTriangles | ( | const Real & | isoValue, |
const int & | subdivideDepth, | ||
CoredMeshData * | mesh, | ||
const int & | fullDepthIso = 0 , |
||
const int & | nonLinearFit = 1 , |
||
bool | addBarycenter = false , |
||
bool | polygonMesh = false |
||
) |
Definition at line 1434 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::GetRestrictedFixedDepthLaplacian | ( | SparseSymmetricMatrix< float > & | matrix, |
const int & | depth, | ||
const int * | entries, | ||
const int & | entryCount, | ||
const TreeOctNode * | rNode, | ||
const Real & | radius, | ||
const SortedTreeNodes & | sNodes | ||
) | [private] |
Definition at line 758 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::GetRoot | ( | const RootInfo & | ri, |
const Real & | isoValue, | ||
const int & | maxDepth, | ||
Point3D< Real > & | position, | ||
hash_map< long long, std::pair< Real, Point3D< Real > > > & | normalHash, | ||
Point3D< Real > * | normal, | ||
const int & | nonLinearFit | ||
) | [private] |
Definition at line 2525 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::GetRoot | ( | const RootInfo & | ri, |
const Real & | isoValue, | ||
Point3D< Real > & | position, | ||
hash_map< long long, std::pair< Real, Point3D< Real > > > & | normalHash, | ||
const int & | nonLinearFit | ||
) | [private] |
Definition at line 2387 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::GetRootIndex | ( | const TreeOctNode * | node, |
const int & | edgeIndex, | ||
const int & | maxDepth, | ||
RootInfo & | ri | ||
) | [static, private] |
Definition at line 2651 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::GetRootIndex | ( | const TreeOctNode * | node, |
const int & | edgeIndex, | ||
const int & | maxDepth, | ||
const int & | sDepth, | ||
RootInfo & | ri | ||
) | [static, private] |
Definition at line 2539 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::GetRootIndex | ( | const long long & | key, |
hash_map< long long, int > & | boundaryRoots, | ||
hash_map< long long, int > * | interiorRoots, | ||
CoredPointIndex & | index | ||
) | [static, private] |
Definition at line 2777 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::GetRootPair | ( | const RootInfo & | root, |
const int & | maxDepth, | ||
RootInfo & | pair | ||
) | [static, private] |
Definition at line 2746 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::HasNormals | ( | TreeOctNode * | node, |
const Real & | epsilon | ||
) | [private] |
Definition at line 1110 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::InteriorFaceRootCount | ( | const TreeOctNode * | node, |
const int & | faceIndex, | ||
const int & | maxDepth | ||
) | [static, private] |
Definition at line 2002 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::IsBoundaryEdge | ( | const TreeOctNode * | node, |
const int & | edgeIndex, | ||
const int & | subdivideDepth | ||
) | [static, private] |
Definition at line 2128 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::IsBoundaryEdge | ( | const TreeOctNode * | node, |
const int & | dir, | ||
const int & | x, | ||
const int & | y, | ||
const int & | subidivideDepth | ||
) | [static, private] |
Definition at line 2137 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::IsBoundaryFace | ( | const TreeOctNode * | node, |
const int & | faceIndex, | ||
const int & | subdivideDepth | ||
) | [static, private] |
Definition at line 2107 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::LaplacianMatrixIteration | ( | const int & | subdivideDepth | ) |
Definition at line 795 of file multi_grid_octree_data.hpp.
double pcl::poisson::Octree< Degree >::MemoryUsage | ( | ) | [static] |
Definition at line 132 of file multi_grid_octree_data.hpp.
void pcl::poisson::Octree< Degree >::NonLinearGetSampleDepthAndWeight | ( | TreeOctNode * | node, |
const Point3D< Real > & | position, | ||
const Real & | samplesPerNode, | ||
Real & | depth, | ||
Real & | weight | ||
) | [private] |
Definition at line 319 of file multi_grid_octree_data.hpp.
Real pcl::poisson::Octree< Degree >::NonLinearGetSampleWeight | ( | TreeOctNode * | node, |
const Point3D< Real > & | position | ||
) | [private] |
Definition at line 347 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::NonLinearSplatOrientedPoint | ( | TreeOctNode * | node, |
const Point3D< Real > & | point, | ||
const Point3D< Real > & | normal | ||
) | [private] |
Definition at line 162 of file multi_grid_octree_data.hpp.
void pcl::poisson::Octree< Degree >::NonLinearSplatOrientedPoint | ( | const Point3D< Real > & | point, |
const Point3D< Real > & | normal, | ||
const int & | kernelDepth, | ||
const Real & | samplesPerNode, | ||
const int & | minDepth, | ||
const int & | maxDepth | ||
) | [private] |
Definition at line 212 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::NonLinearUpdateWeightContribution | ( | TreeOctNode * | node, |
const Point3D< Real > & | position, | ||
const Real & | weight = Real(1.0) |
||
) | [private] |
Definition at line 385 of file multi_grid_octree_data.hpp.
void pcl::poisson::Octree< Degree >::PreValidate | ( | const Real & | isoValue, |
const int & | maxDepth, | ||
const int & | subdivideDepth | ||
) | [private] |
Definition at line 2213 of file multi_grid_octree_data.hpp.
void pcl::poisson::Octree< Degree >::PreValidate | ( | TreeOctNode * | node, |
const Real & | isoValue, | ||
const int & | maxDepth, | ||
const int & | subdivideDepth | ||
) | [private] |
Definition at line 2174 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::SetBoundaryMCRootPositions | ( | const int & | sDepth, |
const Real & | isoValue, | ||
hash_map< long long, int > & | boundaryRoots, | ||
hash_map< long long, std::pair< Real, Point3D< Real > > > & | boundaryNormalHash, | ||
CoredMeshData * | mesh, | ||
const int & | nonLinearFit | ||
) | [private] |
Definition at line 2856 of file multi_grid_octree_data.hpp.
void pcl::poisson::Octree< Degree >::setFunctionData | ( | const PPolynomial< Degree > & | ReconstructionFunction, |
const int & | maxDepth, | ||
const int & | normalize, | ||
const Real & | normalSmooth = -1 |
||
) |
Definition at line 639 of file multi_grid_octree_data.hpp.
void pcl::poisson::Octree< Degree >::SetIsoSurfaceCorners | ( | const Real & | isoValue, |
const int & | subdivisionDepth, | ||
const int & | fullDepthIso | ||
) | [private] |
Definition at line 1752 of file multi_grid_octree_data.hpp.
void pcl::poisson::Octree< Degree >::SetLaplacianWeights | ( | void | ) |
Definition at line 1144 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::SetMCRootPositions | ( | TreeOctNode * | node, |
const int & | sDepth, | ||
const Real & | isoValue, | ||
hash_map< long long, int > & | boundaryRoots, | ||
hash_map< long long, int > * | interiorRoots, | ||
hash_map< long long, std::pair< Real, Point3D< Real > > > & | boundaryNormalHash, | ||
hash_map< long long, std::pair< Real, Point3D< Real > > > * | interiorNormalHash, | ||
std::vector< Point3D< float > > * | interiorPositions, | ||
CoredMeshData * | mesh, | ||
const int & | nonLinearFit | ||
) | [private] |
Definition at line 2801 of file multi_grid_octree_data.hpp.
void pcl::poisson::Octree< Degree >::setNodeIndices | ( | TreeOctNode & | tree, |
int & | idx | ||
) | [private] |
Definition at line 150 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::setTree | ( | boost::shared_ptr< const pcl::PointCloud< PointNT > > | input_, |
const int & | maxDepth, | ||
const int & | kernelDepth, | ||
const Real & | samplesPerNode, | ||
const Real & | scaleFactor, | ||
Point3D< Real > & | center, | ||
Real & | scale, | ||
const int & | resetSamples, | ||
const int & | useConfidence | ||
) |
Definition at line 422 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::SolveFixedDepthMatrix | ( | const int & | depth, |
const SortedTreeNodes & | sNodes | ||
) | [private] |
Definition at line 821 of file multi_grid_octree_data.hpp.
int pcl::poisson::Octree< Degree >::SolveFixedDepthMatrix | ( | const int & | depth, |
const int & | startingDepth, | ||
const SortedTreeNodes & | sNodes | ||
) | [private] |
Definition at line 918 of file multi_grid_octree_data.hpp.
void pcl::poisson::Octree< Degree >::Subdivide | ( | TreeOctNode * | node, |
const Real & | isoValue, | ||
const int & | maxDepth | ||
) | [private] |
Definition at line 1899 of file multi_grid_octree_data.hpp.
void pcl::poisson::Octree< Degree >::Validate | ( | TreeOctNode * | node, |
const Real & | isoValue, | ||
const int & | maxDepth, | ||
const int & | fullDepthIso, | ||
const int & | subdivideDepth | ||
) | [private] |
Definition at line 2306 of file multi_grid_octree_data.hpp.
void pcl::poisson::Octree< Degree >::Validate | ( | TreeOctNode * | node, |
const Real & | isoValue, | ||
const int & | maxDepth, | ||
const int & | fullDepthIso | ||
) | [private] |
Definition at line 2227 of file multi_grid_octree_data.hpp.
FunctionData<Degree,FunctionDataReal> pcl::poisson::Octree< Degree >::fData |
Definition at line 457 of file multi_grid_octree_data.h.
double pcl::poisson::Octree< Degree >::maxMemoryUsage = 0 [static] |
Definition at line 450 of file multi_grid_octree_data.h.
TreeOctNode::NeighborKey pcl::poisson::Octree< Degree >::neighborKey [private] |
Definition at line 131 of file multi_grid_octree_data.h.
TreeOctNode::NeighborKey2 pcl::poisson::Octree< Degree >::neighborKey2 [private] |
Definition at line 132 of file multi_grid_octree_data.h.
std::vector<Point3D<Real> >* pcl::poisson::Octree< Degree >::normals |
Definition at line 454 of file multi_grid_octree_data.h.
Real pcl::poisson::Octree< Degree >::postNormalSmooth |
Definition at line 455 of file multi_grid_octree_data.h.
Real pcl::poisson::Octree< Degree >::radius [private] |
Definition at line 134 of file multi_grid_octree_data.h.
TreeOctNode pcl::poisson::Octree< Degree >::tree |
Definition at line 456 of file multi_grid_octree_data.h.
int pcl::poisson::Octree< Degree >::width [private] |
Definition at line 135 of file multi_grid_octree_data.h.