multi_grid_octree_data.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without modification,
00006 are permitted provided that the following conditions are met:
00007 
00008 Redistributions of source code must retain the above copyright notice, this list of
00009 conditions and the following disclaimer. Redistributions in binary form must reproduce
00010 the above copyright notice, this list of conditions and the following disclaimer
00011 in the documentation and/or other materials provided with the distribution. 
00012 
00013 Neither the name of the Johns Hopkins University nor the names of its contributors
00014 may be used to endorse or promote products derived from this software without specific
00015 prior written permission. 
00016 
00017 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY
00018 EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO THE IMPLIED WARRANTIES 
00019 OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT
00020 SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00021 INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
00022 TO, PROCUREMENT OF SUBSTITUTE  GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR
00023 BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00024 CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00025 ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
00026 DAMAGE.
00027 */
00028 
00029 #ifndef MULTI_GRID_OCTREE_DATA_INCLUDED
00030 #define MULTI_GRID_OCTREE_DATA_INCLUDED
00031 
00032 #if defined __GNUC__
00033 #  pragma GCC system_header
00034 #endif
00035 
00036 #define MISHA_DEBUG 1
00037 
00038 #define GRADIENT_DOMAIN_SOLUTION 1      // Given the constraint vector-field V(p), there are two ways to solve for the coefficients, x, of the indicator function
00039 // with respect to the B-spline basis {B_i(p)}
00040 // 1] Find x minimizing:
00041 //                      || V(p) - \sum_i \nabla x_i B_i(p) ||^2
00042 //              which is solved by the system A_1x = b_1 where:
00043 //                      A_1[i,j] = < \nabla B_i(p) , \nabla B_j(p) >
00044 //                      b_1[i]   = < \nabla B_i(p) , V(p) >
00045 // 2] Formulate this as a Poisson equation:
00046 //                      \sum_i x_i \Delta B_i(p) = \nabla \cdot V(p)
00047 //              which is solved by the system A_2x = b_2 where:
00048 //                      A_2[i,j] = - < \Delta B_i(p) , B_j(p) >
00049 //                      b_2[i]   = - < B_i(p) , \nabla \cdot V(p) >
00050 // Although the two system matrices should be the same (assuming that the B_i satisfy dirichlet/neumann boundary conditions)
00051 // the constraint vectors can differ when V does not satisfy the Neumann boundary conditions:
00052 //              A_1[i,j] = \int_R < \nabla B_i(p) , \nabla B_j(p) >
00053 //               = \int_R [ \nabla \cdot ( B_i(p) \nabla B_j(p) ) - B_i(p) \Delta B_j(p) ]
00054 //               = \int_dR < N(p) , B_i(p) \nabla B_j(p) > + A_2[i,j]
00055 // and the first integral is zero if either f_i is zero on the boundary dR or the derivative of B_i across the boundary is zero.
00056 // However, for the constraints we have:
00057 //              b_1(i)   = \int_R < \nabla B_i(p) , V(p) >
00058 //               = \int_R [ \nabla \cdot ( B_i(p) V(p) ) - B_i(p) \nabla \cdot V(p) ]
00059 //               = \int_dR < N(p) ,  B_i(p) V(p) > + b_2[i]
00060 // In particular, this implies that if the B_i satisfy the Neumann boundary conditions (rather than Dirichlet),
00061 // and V is not zero across the boundary, then the two constraints are different.
00062 // Forcing the < V(p) , N(p) > = 0 on the boundary, by killing off the component of the vector-field in the normal direction
00063 // (FORCE_NEUMANN_FIELD), makes the two systems equal, and the value of this flag should be immaterial.
00064 // Note that under interpretation 1, we have:
00065 //              \sum_i b_1(i) = < \nabla \sum_ i B_i(p) , V(p) > = 0
00066 // because the B_i's sum to one. However, in general, we could have
00067 //              \sum_i b_2(i) \neq 0.
00068 // This could cause trouble because the constant functions are in the kernel of the matrix A, so CG will misbehave if the constraint
00069 // has a non-zero DC term. (Again, forcing < V(p) , N(p) > = 0 along the boundary resolves this problem.)
00070 
00071 #define FORCE_NEUMANN_FIELD 1           // This flag forces the normal component across the boundary of the integration domain to be zero.
00072 // This should be enabled if GRADIENT_DOMAIN_SOLUTION is not, so that CG doesn't run into trouble.
00073 
00074 
00075 #include "hash.h"
00076 #include "bspline_data.h"
00077 
00078 
00079 
00080 namespace pcl
00081 {
00082   namespace poisson
00083   {
00084 
00085     typedef float Real;
00086     typedef float BSplineDataReal;
00087     typedef pcl::poisson::OctNode< class TreeNodeData , Real > TreeOctNode;
00088 
00089 
00090 
00091     class RootInfo
00092     {
00093       public:
00094         const TreeOctNode* node;
00095         int edgeIndex;
00096         long long key;
00097     };
00098 
00099     class VertexData
00100     {
00101       public:
00102         static long long EdgeIndex( const TreeOctNode* node , int eIndex , int maxDepth , int index[DIMENSION] );
00103         static long long EdgeIndex( const TreeOctNode* node , int eIndex , int maxDepth );
00104         static long long FaceIndex( const TreeOctNode* node , int fIndex , int maxDepth,int index[DIMENSION] );
00105         static long long FaceIndex( const TreeOctNode* node , int fIndex , int maxDepth );
00106         static long long CornerIndex( int depth , const int offSet[DIMENSION] , int cIndex , int maxDepth , int index[DIMENSION] );
00107         static long long CornerIndex( const TreeOctNode* node , int cIndex , int maxDepth , int index[DIMENSION] );
00108         static long long CornerIndex( const TreeOctNode* node , int cIndex , int maxDepth );
00109         static long long CenterIndex( int depth , const int offSet[DIMENSION] , int maxDepth , int index[DIMENSION] );
00110         static long long CenterIndex( const TreeOctNode* node , int maxDepth , int index[DIMENSION] );
00111         static long long CenterIndex( const TreeOctNode* node , int maxDepth );
00112         static long long CornerIndexKey( const int index[DIMENSION] );
00113     };
00114     class SortedTreeNodes
00115     {
00116       public:
00117         TreeOctNode** treeNodes;
00118         int *nodeCount;
00119         int maxDepth;
00120         SortedTreeNodes( void );
00121         ~SortedTreeNodes( void );
00122         void set( TreeOctNode& root );
00123         struct CornerIndices
00124         {
00125             int idx[pcl::poisson::Cube::CORNERS];
00126             CornerIndices( void ) { memset( idx , -1 , sizeof( int ) * pcl::poisson::Cube::CORNERS ); }
00127             int& operator[] ( int i ) { return idx[i]; }
00128             const int& operator[] ( int i ) const { return idx[i]; }
00129         };
00130         struct CornerTableData
00131         {
00132             CornerTableData( void ) { cCount=0; }
00133             ~CornerTableData( void ) { clear(); }
00134             void clear( void ) { cTable.clear() ; cCount = 0; }
00135             CornerIndices& operator[] ( const TreeOctNode* node );
00136             const CornerIndices& operator[] ( const TreeOctNode* node ) const;
00137             CornerIndices& cornerIndices( const TreeOctNode* node );
00138             const CornerIndices& cornerIndices( const TreeOctNode* node ) const;
00139             int cCount;
00140             std::vector< CornerIndices > cTable;
00141             std::vector< int > offsets;
00142         };
00143         void setCornerTable( CornerTableData& cData , const TreeOctNode* rootNode , int depth , int threads ) const;
00144         void setCornerTable( CornerTableData& cData , const TreeOctNode* rootNode ,             int threads ) const { setCornerTable( cData , rootNode , maxDepth-1 , threads ); }
00145         void setCornerTable( CornerTableData& cData ,                                           int threads ) const { setCornerTable( cData , treeNodes[0] , maxDepth-1 , threads ); }
00146         int getMaxCornerCount( const TreeOctNode* rootNode , int depth , int maxDepth , int threads ) const ;
00147         struct EdgeIndices
00148         {
00149             int idx[pcl::poisson::Cube::EDGES];
00150             EdgeIndices( void ) { memset( idx , -1 , sizeof( int ) * pcl::poisson::Cube::EDGES ); }
00151             int& operator[] ( int i ) { return idx[i]; }
00152             const int& operator[] ( int i ) const { return idx[i]; }
00153         };
00154         struct EdgeTableData
00155         {
00156             EdgeTableData( void ) { eCount=0; }
00157             ~EdgeTableData( void ) { clear(); }
00158             void clear( void ) { eTable.clear() , eCount=0; }
00159             EdgeIndices& operator[] ( const TreeOctNode* node );
00160             const EdgeIndices& operator[] ( const TreeOctNode* node ) const;
00161             EdgeIndices& edgeIndices( const TreeOctNode* node );
00162             const EdgeIndices& edgeIndices( const TreeOctNode* node ) const;
00163             int eCount;
00164             std::vector< EdgeIndices > eTable;
00165             std::vector< int > offsets;
00166         };
00167         void setEdgeTable( EdgeTableData& eData , const TreeOctNode* rootNode , int depth , int threads );
00168         void setEdgeTable( EdgeTableData& eData , const TreeOctNode* rootNode ,             int threads ) { setEdgeTable( eData , rootNode , maxDepth-1 , threads ); }
00169         void setEdgeTable( EdgeTableData& eData ,                                           int threads ) { setEdgeTable( eData , treeNodes[0] , maxDepth-1 , threads ); }
00170         int getMaxEdgeCount( const TreeOctNode* rootNode , int depth , int threads ) const ;
00171     };
00172 
00173     class TreeNodeData
00174     {
00175       public:
00176         static int UseIndex;
00177         int nodeIndex;
00178         union
00179         {
00180             int mcIndex;
00181             struct
00182             {
00183                 Real centerWeightContribution;
00184                 int normalIndex;
00185             };
00186         };
00187         Real constraint , solution;
00188         int pointIndex;
00189 
00190         TreeNodeData(void);
00191         ~TreeNodeData(void);
00192     };
00193 
00194     template< int Degree >
00195     class Octree
00196     {
00197         SortedTreeNodes _sNodes;
00198         int _minDepth;
00199         bool _constrainValues;
00200         std::vector< int > _pointCount;
00201         struct PointData
00202         {
00203             pcl::poisson::Point3D< Real > position;
00204             Real weight;
00205             Real value;
00206             PointData( pcl::poisson::Point3D< Real > p , Real w , Real v=0 ) { position = p , weight = w , value = v; }
00207         };
00208         std::vector< PointData > _points;
00209         TreeOctNode::NeighborKey3 neighborKey;
00210         TreeOctNode::ConstNeighborKey3 neighborKey2;
00211 
00212         Real radius;
00213         int width;
00214         Real GetLaplacian( const int index[DIMENSION] ) const;
00215         // Note that this is a slight misnomer. We're only taking the diveregence/Laplacian in the weak sense, so there is a change of sign.
00216         Real GetLaplacian( const TreeOctNode* node1 , const TreeOctNode* node2 ) const;
00217         Real GetDivergence( const TreeOctNode* node1 , const TreeOctNode* node2 , const pcl::poisson::Point3D<Real>& normal1 ) const;
00218         Real GetDivergenceMinusLaplacian( const TreeOctNode* node1 , const TreeOctNode* node2 , Real value1 , const pcl::poisson::Point3D<Real>& normal1 ) const;
00219         struct PointInfo
00220         {
00221             float splineValues[3][3];
00222             float weightedValue;
00223         };
00224         Real GetValue( const PointInfo points[3][3][3] , const bool hasPoints[3][3] , const int d[3] ) const;
00225 
00226         class AdjacencyCountFunction
00227         {
00228           public:
00229             int adjacencyCount;
00230             void Function(const TreeOctNode* node1,const TreeOctNode* node2);
00231         };
00232         class AdjacencySetFunction{
00233           public:
00234             int *adjacencies,adjacencyCount;
00235             void Function(const TreeOctNode* node1,const TreeOctNode* node2);
00236         };
00237 
00238         class RefineFunction{
00239           public:
00240             int depth;
00241             void Function(TreeOctNode* node1,const TreeOctNode* node2);
00242         };
00243         class FaceEdgesFunction
00244         {
00245           public:
00246             int fIndex , maxDepth;
00247             std::vector< std::pair< RootInfo , RootInfo > >* edges;
00248             hash_map< long long , std::pair< RootInfo , int > >* vertexCount;
00249             void Function( const TreeOctNode* node1 , const TreeOctNode* node2 );
00250         };
00251 
00252         int SolveFixedDepthMatrix( int depth , const SortedTreeNodes& sNodes , Real* subConstraints ,                     bool showResidual , int minIters , double accuracy );
00253         int SolveFixedDepthMatrix( int depth , const SortedTreeNodes& sNodes , Real* subConstraints , int startingDepth , bool showResidual , int minIters , double accuracy );
00254 
00255         void SetMatrixRowBounds( const TreeOctNode* node , int rDepth , const int rOff[3] , int& xStart , int& xEnd , int& yStart , int& yEnd , int& zStart , int& zEnd ) const;
00256         int GetMatrixRowSize( const TreeOctNode::Neighbors5& neighbors5 ) const;
00257         int GetMatrixRowSize( const TreeOctNode::Neighbors5& neighbors5 , int xStart , int xEnd , int yStart , int yEnd , int zStart , int zEnd ) const;
00258         int SetMatrixRow( const TreeOctNode::Neighbors5& neighbors5 , pcl::poisson::MatrixEntry< float >* row , int offset , const double stencil[5][5][5] ) const;
00259         int SetMatrixRow( const TreeOctNode::Neighbors5& neighbors5 , pcl::poisson::MatrixEntry< float >* row , int offset , const double stencil[5][5][5] , int xStart , int xEnd , int yStart , int yEnd , int zStart , int zEnd ) const;
00260         void SetDivergenceStencil( int depth , pcl::poisson::Point3D< double > *stencil , bool scatter ) const;
00261         void SetLaplacianStencil( int depth , double stencil[5][5][5] ) const;
00262         template< class C , int N > struct Stencil{ C values[N][N][N]; };
00263         void SetLaplacianStencils( int depth , Stencil< double , 5 > stencil[2][2][2] ) const;
00264         void SetDivergenceStencils( int depth , Stencil< pcl::poisson::Point3D< double > , 5 > stencil[2][2][2] , bool scatter ) const;
00265         void SetEvaluationStencils( int depth , Stencil< double , 3 > stencil1[8] , Stencil< double , 3 > stencil2[8][8] ) const;
00266 
00267         static void UpdateCoarserSupportBounds( const TreeOctNode* node , int& startX , int& endX , int& startY , int& endY , int& startZ , int& endZ );
00268         void UpdateConstraintsFromCoarser( const TreeOctNode::NeighborKey5& neighborKey5 , TreeOctNode* node , Real* metSolution , const Stencil< double , 5 >& stencil ) const;
00269         void SetCoarserPointValues( int depth , const SortedTreeNodes& sNodes , Real* metSolution );
00270         Real WeightedCoarserFunctionValue( const TreeOctNode::NeighborKey3& neighborKey3 , const TreeOctNode* node , Real* metSolution ) const;
00271         void UpSampleCoarserSolution( int depth , const SortedTreeNodes& sNodes , pcl::poisson::Vector< Real >& solution ) const;
00272         void DownSampleFinerConstraints( int depth , SortedTreeNodes& sNodes ) const;
00273         template< class C > void DownSample( int depth , const SortedTreeNodes& sNodes , C* constraints ) const;
00274         template< class C > void   UpSample( int depth , const SortedTreeNodes& sNodes , C* coefficients ) const;
00275         int GetFixedDepthLaplacian( pcl::poisson::SparseSymmetricMatrix<float>& matrix , int depth , const SortedTreeNodes& sNodes , Real* subConstraints );
00276         int GetRestrictedFixedDepthLaplacian( pcl::poisson::SparseSymmetricMatrix<float>& matrix , int depth , const int* entries , int entryCount , const TreeOctNode* rNode, Real radius , const SortedTreeNodes& sNodes , Real* subConstraints );
00277 
00278         void SetIsoCorners( Real isoValue , TreeOctNode* leaf , SortedTreeNodes::CornerTableData& cData , char* valuesSet , Real* values , TreeOctNode::ConstNeighborKey3& nKey , const Real* metSolution , const Stencil< double , 3 > stencil1[8] , const Stencil< double , 3 > stencil2[8][8] );
00279         static int IsBoundaryFace( const TreeOctNode* node , int faceIndex , int subdivideDepth );
00280         static int IsBoundaryEdge( const TreeOctNode* node , int edgeIndex , int subdivideDepth );
00281         static int IsBoundaryEdge( const TreeOctNode* node , int dir , int x , int y , int subidivideDepth );
00282 
00283         // For computing the iso-surface there is a lot of re-computation of information across shared geometry.
00284         // For function values we don't care so much.
00285         // For edges we need to be careful so that the mesh remains water-tight
00286         struct RootData : public SortedTreeNodes::CornerTableData , public SortedTreeNodes::EdgeTableData
00287         {
00288             // Edge to iso-vertex map
00289             hash_map< long long , int > boundaryRoots;
00290             // Vertex to ( value , normal ) map
00291             hash_map< long long , std::pair< Real , pcl::poisson::Point3D< Real > > > *boundaryValues;
00292             int* interiorRoots;
00293             Real *cornerValues;
00294             pcl::poisson::Point3D< Real >* cornerNormals;
00295             char *cornerValuesSet , *cornerNormalsSet , *edgesSet;
00296         };
00297 
00298         int SetBoundaryMCRootPositions( int sDepth , Real isoValue , RootData& rootData , pcl::poisson::CoredMeshData* mesh , int nonLinearFit );
00299         int SetMCRootPositions( TreeOctNode* node , int sDepth , Real isoValue , TreeOctNode::ConstNeighborKey5& neighborKey5 , RootData& rootData ,
00300                                 std::vector< pcl::poisson::Point3D< float > >* interiorPositions , pcl::poisson::CoredMeshData* mesh , const Real* metSolution , int nonLinearFit );
00301 #if MISHA_DEBUG
00302         int GetMCIsoTriangles( TreeOctNode* node , pcl::poisson::CoredMeshData* mesh , RootData& rootData ,
00303                                std::vector< pcl::poisson::Point3D< float > >* interiorPositions , int offSet , int sDepth , bool polygonMesh , std::vector< pcl::poisson::Point3D< float > >* barycenters );
00304         static int AddTriangles(  pcl::poisson::CoredMeshData* mesh , std::vector<pcl::poisson::CoredPointIndex>& edges , std::vector<pcl::poisson::Point3D<float> >* interiorPositions , int offSet , bool polygonMesh , std::vector< pcl::poisson::Point3D< float > >* barycenters );
00305 #else // !MISHA_DEBUG
00306         int GetMCIsoTriangles( TreeOctNode* node ,  pcl::poisson::CoredMeshData* mesh , RootData& rootData ,
00307                                std::vector< pcl::poisson::Point3D< float > >* interiorPositions , int offSet , int sDepth , bool addBarycenter , bool polygonMesh );
00308         static int AddTriangles(  pcl::poisson::CoredMeshData* mesh , std::vector<CoredPointIndex>& edges , std::vector<Point3D<float> >* interiorPositions , int offSet , bool addBarycenter , bool polygonMesh );
00309 #endif // MISHA_DEBUG
00310 
00311 
00312         void GetMCIsoEdges( TreeOctNode* node , int sDepth , std::vector< std::pair< RootInfo , RootInfo > >& edges );
00313         static int GetEdgeLoops( std::vector< std::pair< RootInfo , RootInfo > >& edges , std::vector< std::vector< std::pair< RootInfo , RootInfo > > >& loops);
00314         static int InteriorFaceRootCount( const TreeOctNode* node , const int &faceIndex , int maxDepth );
00315         static int EdgeRootCount( const TreeOctNode* node , int edgeIndex , int maxDepth );
00316         static void GetRootSpan( const RootInfo& ri , pcl::poisson::Point3D< float >& start , pcl::poisson::Point3D< float >& end );
00317         int GetRoot( const RootInfo& ri , Real isoValue , TreeOctNode::ConstNeighborKey5& neighborKey5 , pcl::poisson::Point3D<Real> & position , RootData& rootData , int sDepth , const Real* metSolution , int nonLinearFit );
00318         static int GetRootIndex( const TreeOctNode* node , int edgeIndex , int maxDepth , RootInfo& ri );
00319         static int GetRootIndex( const TreeOctNode* node , int edgeIndex , int maxDepth , int sDepth , RootInfo& ri );
00320         static int GetRootIndex( const RootInfo& ri , RootData& rootData , pcl::poisson::CoredPointIndex& index );
00321         static int GetRootPair( const RootInfo& root , int maxDepth , RootInfo& pair );
00322 
00323         int NonLinearUpdateWeightContribution(TreeOctNode* node,const pcl::poisson::Point3D<Real>& position,Real weight=Real(1.0));
00324         Real NonLinearGetSampleWeight(TreeOctNode* node,const pcl::poisson::Point3D<Real>& position);
00325         void NonLinearGetSampleDepthAndWeight(TreeOctNode* node,const pcl::poisson::Point3D<Real>& position,Real samplesPerNode,Real& depth,Real& weight);
00326         int NonLinearSplatOrientedPoint(TreeOctNode* node,const pcl::poisson::Point3D<Real>& point,const pcl::poisson::Point3D<Real>& normal);
00327         Real NonLinearSplatOrientedPoint(const pcl::poisson::Point3D<Real>& point,const pcl::poisson::Point3D<Real>& normal , int kernelDepth , Real samplesPerNode , int minDepth , int maxDepth);
00328 
00329         int HasNormals(TreeOctNode* node,Real epsilon);
00330         Real getCornerValue( const TreeOctNode::ConstNeighborKey3& neighborKey3 , const TreeOctNode* node , int corner , const Real* metSolution );
00331         pcl::poisson::Point3D< Real > getCornerNormal( const TreeOctNode::ConstNeighborKey5& neighborKey5 , const TreeOctNode* node , int corner , const Real* metSolution );
00332         Real getCornerValue( const TreeOctNode::ConstNeighborKey3& neighborKey3 , const TreeOctNode* node , int corner , const Real* metSolution , const double stencil1[3][3][3] , const double stencil2[3][3][3] );
00333         Real getCenterValue( const TreeOctNode::ConstNeighborKey3& neighborKey3 , const TreeOctNode* node );
00334       public:
00335         int threads;
00336         static double maxMemoryUsage;
00337         static double MemoryUsage( void );
00338         std::vector< pcl::poisson::Point3D<Real> >* normals;
00339         Real postNormalSmooth;
00340         TreeOctNode tree;
00341         pcl::poisson::BSplineData<Degree,BSplineDataReal> fData;
00342         Octree( void );
00343 
00344         void setBSplineData( int maxDepth , Real normalSmooth=-1 , bool reflectBoundary=false );
00345         void finalize( void );
00346         void RefineBoundary( int subdivisionDepth );
00347         Real* GetWeightGrid( int& res , int depth=-1 );
00348         Real* GetSolutionGrid( int& res , float isoValue=0.f , int depth=-1 );
00349 
00350         template<typename PointNT> int
00351         setTree( boost::shared_ptr<const pcl::PointCloud<PointNT> > input_ , int maxDepth , int minDepth ,
00352                  int kernelDepth , Real samplesPerNode , Real scaleFactor , Point3D<Real>& center , Real& scale ,
00353                  int useConfidence , Real constraintWeight , bool adaptiveWeights );
00354 
00355         void SetLaplacianConstraints(void);
00356         void ClipTree(void);
00357         int LaplacianMatrixIteration( int subdivideDepth , bool showResidual , int minIters , double accuracy );
00358 
00359         Real GetIsoValue(void);
00360         void GetMCIsoTriangles( Real isoValue , int subdivideDepth ,  pcl::poisson::CoredMeshData* mesh , int fullDepthIso=0 , int nonLinearFit=1 , bool addBarycenter=false , bool polygonMesh=false );
00361     };
00362 
00363 
00364   }
00365 }
00366 
00367 
00368 
00369 
00370 #include "multi_grid_octree_data.hpp"
00371 #endif // MULTI_GRID_OCTREE_DATA_INCLUDED


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:25:40