marching_cubes_poisson.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: marching_cubes_poisson.h 5531 2012-04-08 09:14:33Z aichim $
00039  *
00040  */
00041 
00042 #ifndef PCL_POISSON_MARCHING_CUBES_POISSON_H_
00043 #define PCL_POISSON_MARCHING_CUBES_POISSON_H_
00044 
00045 #include <vector>
00046 #include "geometry.h"
00047 
00048 
00049 namespace pcl {
00050   namespace poisson {
00051 
00052 
00053     class Square
00054     {
00055     public:
00056       const static int CORNERS = 4, EDGES = 4, NEIGHBORS = 4;
00057       static int  CornerIndex (const int& x, const int& y);
00058       static void FactorCornerIndex (const int& idx, int& x, int& y);
00059       static int  EdgeIndex (const int& orientation, const int& i);
00060       static void FactorEdgeIndex (const int& idx, int& orientation, int& i);
00061 
00062       static int  ReflectCornerIndex (const int& idx, const int& edgeIndex);
00063       static int  ReflectEdgeIndex (const int& idx, const int& edgeIndex);
00064 
00065       static void EdgeCorners (const int& idx, int& c1, int &c2);
00066     };
00067 
00068     class Cube{
00069     public:
00070       const static int CORNERS = 8, EDGES = 12, NEIGHBORS = 6;
00071 
00072       static int CornerIndex (const int& x, const int& y, const int& z);
00073       static void FactorCornerIndex (const int& idx, int& x, int& y, int& z);
00074       static int EdgeIndex (const int& orientation, const int& i, const int& j);
00075       static void FactorEdgeIndex (const int& idx, int& orientation, int& i, int &j);
00076       static int FaceIndex (const int& dir, const int& offSet);
00077       static int FaceIndex (const int& x, const int& y, const int& z);
00078       static void FactorFaceIndex (const int& idx, int& x, int &y, int& z);
00079       static void FactorFaceIndex (const int& idx, int& dir, int& offSet);
00080 
00081       static int AntipodalCornerIndex (const int& idx);
00082       static int FaceReflectCornerIndex (const int& idx, const int& faceIndex);
00083       static int FaceReflectEdgeIndex (const int& idx, const int& faceIndex);
00084       static int FaceReflectFaceIndex (const int& idx, const int& faceIndex);
00085       static int EdgeReflectCornerIndex (const int& idx, const int& edgeIndex);
00086       static int EdgeReflectEdgeIndex (const int& edgeIndex);
00087 
00088       static int FaceAdjacentToEdges (const int& eIndex1, const int& eIndex2);
00089       static void FacesAdjacentToEdge (const int& eIndex, int& f1Index, int& f2Index);
00090 
00091       static void EdgeCorners (const int& idx, int& c1, int &c2);
00092       static void FaceCorners (const int& idx, int& c1, int &c2, int& c3, int& c4);
00093     };
00094 
00095     class MarchingSquares
00096     {
00097       static double Interpolate (const double& v1, const double& v2);
00098       static void SetVertex (const int& e, const double values[Square::CORNERS], const double& iso);
00099     public:
00100       const static int MAX_EDGES = 2;
00101       static const int edgeMask[1<<Square::CORNERS];
00102       static const int edges[1<<Square::CORNERS][2*MAX_EDGES+1];
00103       static double vertexList[Square::EDGES][2];
00104 
00105       static int GetIndex (const double values[Square::CORNERS], const double& iso);
00106       static int IsAmbiguous (const double v[Square::CORNERS] ,const double& isoValue);
00107       static int AddEdges (const double v[Square::CORNERS], const double& isoValue, Edge* edges);
00108       static int AddEdgeIndices (const double v[Square::CORNERS], const double& isoValue, int* edges);
00109     };
00110 
00111     class MarchingCubes
00112     {
00113       static double Interpolate (const double& v1, const double& v2);
00114       static void SetVertex (const int& e, const double values[Cube::CORNERS], const double& iso);
00115       static int GetFaceIndex (const double values[Cube::CORNERS], const double& iso, const int& faceIndex);
00116 
00117       static float Interpolate (const float& v1, const float& v2);
00118       static void SetVertex (const int& e, const float values[Cube::CORNERS], const float& iso);
00119       static int GetFaceIndex (const float values[Cube::CORNERS], const float& iso, const int& faceIndex);
00120 
00121       static int GetFaceIndex (const int& mcIndex, const int& faceIndex);
00122     public:
00123       const static int MAX_TRIANGLES=5;
00124       static const int edgeMask[1<<Cube::CORNERS];
00125       static const int triangles[1<<Cube::CORNERS][3*MAX_TRIANGLES+1];
00126       static const int cornerMap[Cube::CORNERS];
00127       static double vertexList[Cube::EDGES][3];
00128 
00129       static int AddTriangleIndices (const int& mcIndex, int* triangles);
00130 
00131       static int GetIndex (const double values[Cube::CORNERS],const double& iso);
00132       static int IsAmbiguous (const double v[Cube::CORNERS],const double& isoValue,const int& faceIndex);
00133       static int HasRoots (const double v[Cube::CORNERS],const double& isoValue);
00134       static int HasRoots (const double v[Cube::CORNERS],const double& isoValue,const int& faceIndex);
00135       static int AddTriangles (const double v[Cube::CORNERS],const double& isoValue,Triangle* triangles);
00136       static int AddTriangleIndices (const double v[Cube::CORNERS],const double& isoValue,int* triangles);
00137 
00138       static int GetIndex (const float values[Cube::CORNERS], const float& iso);
00139       static int IsAmbiguous (const float v[Cube::CORNERS], const float& isoValue, const int& faceIndex);
00140       static int HasRoots (const float v[Cube::CORNERS], const float& isoValue);
00141       static int HasRoots (const float v[Cube::CORNERS], const float& isoValue, const int& faceIndex);
00142       static int AddTriangles (const float v[Cube::CORNERS], const float& isoValue, Triangle* triangles);
00143       static int AddTriangleIndices (const float v[Cube::CORNERS], const float& isoValue, int* triangles);
00144 
00145       static int IsAmbiguous (const int& mcIndex, const int& faceIndex);
00146       static int HasRoots (const int& mcIndex);
00147       static int HasFaceRoots (const int& mcIndex, const int& faceIndex);
00148       static int HasEdgeRoots (const int& mcIndex, const int& edgeIndex);
00149     };
00150 
00151 
00152   }
00153 }
00154 
00155 #endif /* PCL_POISSON_MARCHING_CUBES_POISSON_H_ */


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