multi_grid_octree_data.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2009-2012, Willow Garage, Inc.
00006  *  Copyright (c) 2006, Michael Kazhdan and Matthew Bolitho,
00007  *                      Johns Hopkins University
00008  *
00009  *  All rights reserved.
00010  *
00011  *  Redistribution and use in source and binary forms, with or without
00012  *  modification, are permitted provided that the following conditions
00013  *  are met:
00014  *
00015  *   * Redistributions of source code must retain the above copyright
00016  *     notice, this list of conditions and the following disclaimer.
00017  *   * Redistributions in binary form must reproduce the above
00018  *     copyright notice, this list of conditions and the following
00019  *     disclaimer in the documentation and/or other materials provided
00020  *     with the distribution.
00021  *   * Neither the name of Willow Garage, Inc. nor the names of its
00022  *     contributors may be used to endorse or promote products derived
00023  *     from this software without specific prior written permission.
00024  *
00025  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00026  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00027  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00028  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00029  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00030  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00031  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00032  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00033  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00034  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00035  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00036  *  POSSIBILITY OF SUCH DAMAGE.
00037  *
00038  * $Id: multi_grid_octree_data.h 5531 2012-04-08 09:14:33Z aichim $
00039  *
00040  */
00041 
00042 #ifndef PCL_POISSON_MULTI_GRID_OCTREE_DATA_H_
00043 #define PCL_POISSON_MULTI_GRID_OCTREE_DATA_H_
00044 
00045 #include "hash.h"
00046 
00047 namespace pcl 
00048 {
00049   namespace poisson 
00050   {
00051     typedef float Real;
00052     typedef float FunctionDataReal;
00053     typedef OctNode<class TreeNodeData,Real> TreeOctNode;
00054 
00055     class RootInfo
00056     {
00057       public:
00058         const TreeOctNode* node;
00059         int edgeIndex;
00060         long long key;
00061     };
00062 
00063     class VertexData
00064     {
00065       public:
00066         static long long 
00067         EdgeIndex (const TreeOctNode* node, const int& eIndex, const int& maxDepth, int index[DIMENSION]);
00068 
00069         static long long 
00070         EdgeIndex (const TreeOctNode* node, const int& eIndex, const int& maxDepth);
00071 
00072         static long long 
00073         FaceIndex (const TreeOctNode* node, const int& fIndex, const int& maxDepth, int index[DIMENSION]);
00074 
00075         static long long 
00076         FaceIndex (const TreeOctNode* node, const int& fIndex, const int& maxDepth);
00077 
00078         static long long 
00079         CornerIndex (const int& depth, const int offSet[DIMENSION] ,const int& cIndex, const int& maxDepth, int index[DIMENSION]);
00080 
00081         static long long 
00082         CornerIndex (const TreeOctNode* node, const int& cIndex, const int& maxDepth, int index[DIMENSION]);
00083 
00084         static long long 
00085         CornerIndex (const TreeOctNode* node, const int& cIndex, const int& maxDepth);
00086 
00087         static long long 
00088         CenterIndex (const int& depth, const int offSet[DIMENSION], const int& maxDepth, int index[DIMENSION]);
00089 
00090         static long long 
00091         CenterIndex (const TreeOctNode* node, const int& maxDepth, int index[DIMENSION]);
00092         
00093         static long long 
00094         CenterIndex (const TreeOctNode* node, const int& maxDepth);
00095     };
00096 
00097     class SortedTreeNodes
00098     {
00099       public:
00100         TreeOctNode** treeNodes;
00101         int *nodeCount;
00102         int maxDepth;
00103         SortedTreeNodes ();
00104         ~SortedTreeNodes ();
00105         void 
00106         set (TreeOctNode& root,const int& setIndex);
00107     };
00108 
00109     class TreeNodeData
00110     {
00111       public:
00112         static int UseIndex;
00113         union
00114         {
00115           int mcIndex;
00116           struct
00117           {
00118             int nodeIndex;
00119             Real centerWeightContribution;
00120           };
00121         };
00122         Real value;
00123 
00124         TreeNodeData (void);
00125         ~TreeNodeData (void);
00126     };
00127 
00128     template<int Degree>
00129     class Octree
00130     {
00131       TreeOctNode::NeighborKey neighborKey;
00132       TreeOctNode::NeighborKey2 neighborKey2;
00133 
00134       Real radius;
00135       int width;
00136 
00137       void 
00138       setNodeIndices (TreeOctNode& tree,int& idx);
00139       
00140       Real 
00141       GetDotProduct (const int index[DIMENSION]) const;
00142 
00143       Real 
00144       GetLaplacian (const int index[DIMENSION]) const;
00145 
00146       Real 
00147       GetDivergence (const int index[DIMENSION], const Point3D<Real>& normal) const;
00148 
00149       class DivergenceFunction
00150       {
00151         public:
00152           Point3D<Real> normal;
00153           Octree<Degree>* ot;
00154           int index[DIMENSION],scratch[DIMENSION];
00155 
00156           void 
00157           Function (TreeOctNode* node1, const TreeOctNode* node2);
00158       };
00159 
00160       class LaplacianProjectionFunction
00161       {
00162         public:
00163           double value;
00164           Octree<Degree>* ot;
00165           int index[DIMENSION],scratch[DIMENSION];
00166 
00167           void 
00168           Function (TreeOctNode* node1, const TreeOctNode* node2);
00169       };
00170 
00171       class LaplacianMatrixFunction
00172       {
00173         public:
00174           int x2,y2,z2,d2;
00175           Octree<Degree>* ot;
00176           int index[DIMENSION],scratch[DIMENSION];
00177           int elementCount,offset;
00178           MatrixEntry<float>* rowElements;
00179 
00180           int 
00181           Function (const TreeOctNode* node1, const TreeOctNode* node2);
00182       };
00183 
00184       class RestrictedLaplacianMatrixFunction
00185       {
00186         public:
00187           int depth,offset[3];
00188           Octree<Degree>* ot;
00189           Real radius;
00190           int index[DIMENSION], scratch[DIMENSION];
00191           int elementCount;
00192           MatrixEntry<float>* rowElements;
00193 
00194           int 
00195           Function (const TreeOctNode* node1, const TreeOctNode* node2);
00196       };
00197 
00199       // Evaluation Functions  //
00201       class PointIndexValueFunction
00202       {
00203         public:
00204           int res2;
00205           FunctionDataReal* valueTables;
00206           int index[DIMENSION];
00207           Real value;
00208 
00209           void 
00210           Function (const TreeOctNode* node);
00211       };
00212 
00213       class PointIndexValueAndNormalFunction
00214       {
00215         public:
00216           int res2;
00217           FunctionDataReal* valueTables;
00218           FunctionDataReal* dValueTables;
00219           Real value;
00220           Point3D<Real> normal;
00221           int index[DIMENSION];
00222 
00223           void 
00224           Function (const TreeOctNode* node);
00225       };
00226 
00227       class AdjacencyCountFunction
00228       {
00229         public:
00230           int adjacencyCount;
00231 
00232           void 
00233           Function (const TreeOctNode* node1, const TreeOctNode* node2);
00234       };
00235 
00236       class AdjacencySetFunction
00237       {
00238         public:
00239           int *adjacencies,adjacencyCount;
00240           void 
00241           Function (const TreeOctNode* node1, const TreeOctNode* node2);
00242       };
00243 
00244       class RefineFunction
00245       {
00246         public:
00247           int depth;
00248           void 
00249           Function (TreeOctNode* node1, const TreeOctNode* node2);
00250       };
00251 
00252       class FaceEdgesFunction 
00253       {
00254         public:
00255           int fIndex,maxDepth;
00256           std::vector<std::pair<long long,long long> >* edges;
00257           hash_map<long long, std::pair<RootInfo,int> >* vertexCount;
00258 
00259           void 
00260           Function (const TreeOctNode* node1, const TreeOctNode* node2);
00261       };
00262 
00263       int 
00264       SolveFixedDepthMatrix (const int& depth, const SortedTreeNodes& sNodes);
00265       
00266       int 
00267       SolveFixedDepthMatrix (const int& depth, const int& startingDepth, const SortedTreeNodes& sNodes);
00268 
00269       int 
00270       GetFixedDepthLaplacian (SparseSymmetricMatrix<float>& matrix, const int& depth, const SortedTreeNodes& sNodes);
00271 
00272       int 
00273       GetRestrictedFixedDepthLaplacian (SparseSymmetricMatrix<float>& matrix,
00274                                         const int& depth,
00275                                         const int* entries,
00276                                         const int& entryCount,
00277                                         const TreeOctNode* rNode,
00278                                         const Real& radius,
00279                                         const SortedTreeNodes& sNodes);
00280 
00281       void 
00282       SetIsoSurfaceCorners (const Real& isoValue, const int& subdivisionDepth, const int& fullDepthIso);
00283 
00284       static int 
00285       IsBoundaryFace (const TreeOctNode* node, const int& faceIndex, const int& subdivideDepth);
00286       
00287       static int 
00288       IsBoundaryEdge (const TreeOctNode* node, const int& edgeIndex, const int& subdivideDepth);
00289       
00290       static int 
00291       IsBoundaryEdge (const TreeOctNode* node, const int& dir, const int& x, const int& y, const int& subidivideDepth);
00292       
00293       void 
00294       PreValidate (const Real& isoValue, const int& maxDepth, const int& subdivideDepth);
00295       
00296       void 
00297       PreValidate (TreeOctNode* node, const Real& isoValue, const int& maxDepth, const int& subdivideDepth);
00298       
00299       void 
00300       Validate (TreeOctNode* node,
00301                 const Real& isoValue,
00302                 const int& maxDepth,
00303                 const int& fullDepthIso,
00304                 const int& subdivideDepth);
00305 
00306       void 
00307       Validate (TreeOctNode* node, const Real& isoValue, const int& maxDepth, const int& fullDepthIso);
00308 
00309       void 
00310       Subdivide (TreeOctNode* node, const Real& isoValue, const int& maxDepth);
00311 
00312       int 
00313       SetBoundaryMCRootPositions (const int& sDepth,const Real& isoValue,
00314                                   hash_map<long long,int>& boundaryRoots,
00315                                   hash_map<long long,
00316                                   std::pair<Real,Point3D<Real> > >& boundaryNormalHash,
00317                                   CoredMeshData* mesh,
00318                                   const int& nonLinearFit);
00319 
00320       int 
00321       SetMCRootPositions (TreeOctNode* node,
00322                           const int& sDepth,
00323                           const Real& isoValue,
00324                           hash_map<long long, int>& boundaryRoots,
00325                           hash_map<long long, int>* interiorRoots,
00326                           hash_map<long long, std::pair<Real,Point3D<Real> > >& boundaryNormalHash,
00327                           hash_map<long long, std::pair<Real,Point3D<Real> > >* interiorNormalHash,
00328                           std::vector<Point3D<float> >* interiorPositions,
00329                           CoredMeshData* mesh,
00330                           const int& nonLinearFit);
00331 
00332       int 
00333       GetMCIsoTriangles (TreeOctNode* node,
00334                          CoredMeshData* mesh,
00335                          hash_map<long long,int>& boundaryRoots,
00336                          hash_map<long long,int>* interiorRoots,
00337                          std::vector<Point3D<float> >* interiorPositions,
00338                          const int& offSet,
00339                          const int& sDepth, 
00340                          bool addBarycenter, 
00341                          bool polygonMesh);
00342 
00343       static int 
00344       AddTriangles (CoredMeshData* mesh,
00345                     std::vector<CoredPointIndex> edges[3],
00346                     std::vector<Point3D<float> >* interiorPositions, 
00347                     const int& offSet);
00348       
00349       static int 
00350       AddTriangles (CoredMeshData* mesh, 
00351                     std::vector<CoredPointIndex>& edges, std::vector<Point3D<float> >* interiorPositions, 
00352                     const int& offSet, 
00353                     bool addBarycenter, 
00354                     bool polygonMesh);
00355 
00356       void 
00357       GetMCIsoEdges (TreeOctNode* node,
00358                      hash_map<long long,int>& boundaryRoots,
00359                      hash_map<long long,int>* interiorRoots,
00360                      const int& sDepth,
00361                      std::vector<std::pair<long long,long long> >& edges);
00362 
00363       static int 
00364       GetEdgeLoops (std::vector<std::pair<long long,long long> >& edges,
00365                     std::vector<std::vector<std::pair<long long,long long> > >& loops);
00366 
00367       static int 
00368       InteriorFaceRootCount (const TreeOctNode* node,const int &faceIndex,const int& maxDepth);
00369 
00370       static int 
00371       EdgeRootCount (const TreeOctNode* node,const int& edgeIndex,const int& maxDepth);
00372 
00373       int 
00374       GetRoot (const RootInfo& ri,
00375                const Real& isoValue,
00376                const int& maxDepth,Point3D<Real> & position,
00377                hash_map<long long,std::pair<Real,Point3D<Real> > >& normalHash,
00378                Point3D<Real>* normal,
00379                const int& nonLinearFit);
00380 
00381       int 
00382       GetRoot (const RootInfo& ri,
00383                const Real& isoValue,
00384                Point3D<Real> & position,
00385                hash_map<long long,
00386                std::pair<Real,Point3D<Real> > >& normalHash,
00387                const int& nonLinearFit);
00388 
00389       static int 
00390       GetRootIndex (const TreeOctNode* node,const int& edgeIndex,const int& maxDepth,RootInfo& ri);
00391 
00392       static int 
00393       GetRootIndex (const TreeOctNode* node, 
00394                     const int& edgeIndex,
00395                     const int& maxDepth,
00396                     const int& sDepth,
00397                     RootInfo& ri);
00398       
00399       static int 
00400       GetRootIndex (const long long& key,
00401                     hash_map<long long,int>& boundaryRoots,
00402                     hash_map<long long,int>* interiorRoots,
00403                     CoredPointIndex& index);
00404       
00405       static int 
00406       GetRootPair (const RootInfo& root,const int& maxDepth,RootInfo& pair);
00407 
00408       int 
00409       NonLinearUpdateWeightContribution (TreeOctNode* node,
00410                                          const Point3D<Real>& position,
00411                                          const Real& weight = Real(1.0));
00412 
00413       Real 
00414       NonLinearGetSampleWeight (TreeOctNode* node,
00415                                 const Point3D<Real>& position);
00416       
00417       void 
00418       NonLinearGetSampleDepthAndWeight (TreeOctNode* node,
00419                                         const Point3D<Real>& position,
00420                                         const Real& samplesPerNode,
00421                                         Real& depth,
00422                                         Real& weight);
00423 
00424       int 
00425       NonLinearSplatOrientedPoint (TreeOctNode* node,
00426                                    const Point3D<Real>& point,
00427                                    const Point3D<Real>& normal);
00428       
00429       void 
00430       NonLinearSplatOrientedPoint (const Point3D<Real>& point,
00431                                    const Point3D<Real>& normal,
00432                                    const int& kernelDepth,
00433                                    const Real& samplesPerNode,
00434                                    const int& minDepth,
00435                                    const int& maxDepth);
00436 
00437       int 
00438       HasNormals (TreeOctNode* node,const Real& epsilon);
00439 
00440       Real 
00441       getCenterValue (const TreeOctNode* node);
00442 
00443       Real 
00444       getCornerValue (const TreeOctNode* node,const int& corner);
00445 
00446       void 
00447       getCornerValueAndNormal (const TreeOctNode* node,const int& corner,Real& value,Point3D<Real>& normal);
00448 
00449       public:
00450         static double maxMemoryUsage;
00451         static double 
00452         MemoryUsage ();
00453 
00454         std::vector<Point3D<Real> >* normals;
00455         Real postNormalSmooth;
00456         TreeOctNode tree;
00457         FunctionData<Degree,FunctionDataReal> fData;
00458         Octree ();
00459 
00460         void 
00461         setFunctionData (const PPolynomial<Degree>& ReconstructionFunction,
00462                          const int& maxDepth,
00463                          const int& normalize,
00464                          const Real& normalSmooth = -1);
00465         
00466         void 
00467         finalize1 (const int& refineNeighbors=-1);
00468         
00469         void 
00470         finalize2 (const int& refineNeighbors=-1);
00471 
00472         //int setTree(char* fileName,const int& maxDepth,const int& binary,const int& kernelDepth,const Real& samplesPerNode,
00473         //      const Real& scaleFactor,Point3D<Real>& center,Real& scale,const int& resetSampleDepths,const int& useConfidence);
00474 
00475         template<typename PointNT> int
00476         setTree (boost::shared_ptr<const pcl::PointCloud<PointNT> > input_,
00477                  const int& maxDepth,
00478                  const int& kernelDepth,
00479                  const Real& samplesPerNode,
00480                  const Real& scaleFactor,
00481                  Point3D<Real>& center,
00482                  Real& scale,
00483                  const int& resetSamples,
00484                  const int& useConfidence);
00485 
00486 
00487         void 
00488         SetLaplacianWeights (void);
00489         
00490         void 
00491         ClipTree (void);
00492 
00493         int 
00494         LaplacianMatrixIteration (const int& subdivideDepth);
00495 
00496         Real 
00497         GetIsoValue (void);
00498         
00499         void 
00500         GetMCIsoTriangles (const Real& isoValue,
00501                            CoredMeshData* mesh,
00502                            const int& fullDepthIso = 0,
00503                            const int& nonLinearFit = 1, 
00504                            bool addBarycenter = false, 
00505                            bool polygonMesh = false);
00506         
00507         void 
00508         GetMCIsoTriangles (const Real& isoValue,
00509                            const int& subdivideDepth,
00510                            CoredMeshData* mesh,
00511                            const int& fullDepthIso = 0,
00512                            const int& nonLinearFit = 1, 
00513                            bool addBarycenter = false, 
00514                            bool polygonMesh = false );
00515     };
00516   }
00517 }
00518 
00519 
00520 #include <pcl/surface/impl/poisson/multi_grid_octree_data.hpp>
00521 #endif /* PCL_POISSON_MULTI_GRID_OCTREE_DATA_H_ */


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:15:44