A surface reconstruction object that implements the standard marching cubes algorithm using a octree and a thread pool for parallel computation. More...
#include <DMCReconstruction.hpp>

| Public Member Functions | |
| DMCReconstruction (PointsetSurfacePtr< BaseVecT > surface, BoundingBox< BaseVecT > bb, bool dual, int maxLevel, float maxError) | |
| Constructor.  More... | |
| virtual void | getMesh (BaseMesh< BaseVecT > &mesh) | 
| Returns the surface reconstruction of the given point set.  More... | |
| virtual void | getMesh (BaseMesh< BaseVecT > &mesh, BoundingBox< BaseVecT > &bb, vector< unsigned int > &duplicates, float comparePrecision) | 
| virtual | ~DMCReconstruction () | 
| Destructor.  More... | |
|  Public Member Functions inherited from lvr2::FastReconstructionBase< BaseVecT > | |
| virtual | ~FastReconstructionBase ()=default | 
|  Public Member Functions inherited from lvr2::PointsetMeshGenerator< BaseVecT > | |
| PointsetMeshGenerator (PointsetSurfacePtr< BaseVecT > surface) | |
| Constructs a Reconstructor object using the given point set surface.  More... | |
| Protected Member Functions | |
| void | buildTree (C_Octree< BaseVecT, BoxT, my_dummy > &parent, int levels, bool dual) | 
| Builds a tree level respectively creates the child nodes of a root node.  More... | |
| void | detectVertexForDualCell (C_Octree< BaseVecT, BoxT, my_dummy > &octree, CellHandle ch, int cells, float max_bb_width, uint pos, int onEdge, BaseVecT &feature) | 
| Calculates the position of a aspecific point in a dual cell.  More... | |
| void | drawOctree (C_Octree< BaseVecT, BoxT, my_dummy > &parent) | 
| Saves the octree as wireframe. WORKS ONLY SINGLE THREADED!  More... | |
| float | edgeEquation (BaseVecT p, BaseVecT v1, BaseVecT v2) | 
| Calculates whether the given vertex lies left, right or on the given line.  More... | |
| float | getDistance (BaseVecT p, BaseVecT v1, BaseVecT v2) | 
| Calculates the distance between a point and a line.  More... | |
| float | getDistance (BaseVecT p, BaseVecT v1, BaseVecT v2, BaseVecT v3) | 
| Calculates the distance between a point and a triangle.  More... | |
| float | getDistance (BaseVecT v1, BaseVecT v2) | 
| Calculates the distance between to points.  More... | |
| DualLeaf< BaseVecT, BoxT > * | getDualLeaf (CellHandle &cell, int cells, C_Octree< BaseVecT, BoxT, my_dummy > &octree, char pos) | 
| Builds a dual cell at given position.  More... | |
| void | getRotationMatrix (float matrix[9], BaseVecT v1, BaseVecT v2, BaseVecT v3) | 
| Calculates a rotation matrix for a triangle that rotates it into xy.  More... | |
| void | getSurface (BaseMesh< BaseVecT > &mesh, DualLeaf< BaseVecT, BoxT > *leaf, int cells, short level) | 
| Performs a local reconstruction according to the standard Marching Cubes table from Paul Bourke.  More... | |
| void | matrixDotVector (float *matrix, BaseVecT *vector) | 
| Performs a matrix multiplication.  More... | |
| void | traverseTree (BaseMesh< BaseVecT > &mesh, C_Octree< BaseVecT, BoxT, my_dummy > &octree) | 
| Traverses the octree and insert for each leaf the getSurface-function into the thread pool.  More... | |
| Protected Attributes | |
| float | bb_longestSide | 
| BaseVecT | bb_max | 
| BaseVecT | bb_min | 
| float | bb_size [3] | 
| std::vector< BaseVecT > | dualVertices | 
| BaseVecT | m_boundingBoxCenter | 
| bool | m_dual | 
| uint | m_leaves | 
| float | m_maxError | 
| int | m_maxLevel | 
| unique_ptr< DMCPointHandle< BaseVecT > > | m_pointHandler | 
| ProgressBar * | m_progressBar | 
| C_Octree< BaseVecT, BoxT, my_dummy > * | octree | 
|  Protected Attributes inherited from lvr2::PointsetMeshGenerator< BaseVecT > | |
| PointsetSurfacePtr< BaseVecT > | m_surface | 
| The point cloud manager that handles the loaded point cloud data.  More... | |
A surface reconstruction object that implements the standard marching cubes algorithm using a octree and a thread pool for parallel computation.
Definition at line 67 of file DMCReconstruction.hpp.
| lvr2::DMCReconstruction< BaseVecT, BoxT >::DMCReconstruction | ( | PointsetSurfacePtr< BaseVecT > | surface, | 
| BoundingBox< BaseVecT > | bb, | ||
| bool | dual, | ||
| int | maxLevel, | ||
| float | maxError | ||
| ) | 
Constructor.
| surface | Pointer to the surface | 
| bb | BoundingBox of the PointCloud | 
| dual | |
| maxLevel | Max allowed octree level | 
| maxError | Max allowed error between points and surfaces | 
| 
 | virtual | 
Destructor.
| 
 | protected | 
Builds a tree level respectively creates the child nodes of a root node.
| parentPoints | Points inside the parent node. | 
| parent | Reference to the parent node. | 
| childCenter | Centers of the children. | 
| size | Actually voxelsize. | 
| parentCenter | Center of the parent node. | 
| 
 | protected | 
Calculates the position of a aspecific point in a dual cell.
| octree | The current octree instace | 
| ch | The current cellHandle of the octree | 
| cells | Number of possible cells at current level | 
| max_bb_width | Width of the bounding box | 
| pos | Position of the dual cell relative to the given cell | 
| onEdge | Indicator whether the wished position lies on an edge | 
| feature | Vector that should be filles with the correct position | 
| 
 | protected | 
Saves the octree as wireframe. WORKS ONLY SINGLE THREADED!
| parent | The octree | 
| 
 | protected | 
Calculates whether the given vertex lies left, right or on the given line.
| p | Vertex to check position for | 
| v1 | First point of the line | 
| v2 | Second point of the line | 
| 
 | protected | 
Calculates the distance between a point and a line.
| p | Vertex to calculate distance for | 
| v1 | First point of the line | 
| v2 | Second point of the line | 
| 
 | protected | 
Calculates the distance between a point and a triangle.
| p | Vertex to calculate distance for | 
| v1 | First point of the triangle | 
| v2 | Second point of the triangle | 
| v3 | Third point of the triangle | 
| 
 | protected | 
Calculates the distance between to points.
| p | Vertex to calculate distance for | 
| v1 | Point | 
| 
 | protected | 
Builds a dual cell at given position.
| cell | Cell of the regual octree | 
| cells | number of cells at the cells octree level | 
| octree | Reference to the octree | 
| pos | Position of the specific dual cell | 
| 
 | virtual | 
Returns the surface reconstruction of the given point set.
| mesh | 
Implements lvr2::FastReconstructionBase< BaseVecT >.
| 
 | virtual | 
Implements lvr2::FastReconstructionBase< BaseVecT >.
| 
 | protected | 
Calculates a rotation matrix for a triangle that rotates it into xy.
| matrix | Array the matrix should be written in | 
| v1 | First point of the triangle | 
| v2 | Second point of the triangle | 
| v3 | Third point of the triangle | 
| 
 | protected | 
Performs a local reconstruction according to the standard Marching Cubes table from Paul Bourke.
| mesh | The reconstructed mesh | 
| leaf | A octree leaf. | 
| cells | 
| 
 | protected | 
Performs a matrix multiplication.
| matrix | Pointer to the matrix | 
| vector | Pointer to th vector | 
| 
 | protected | 
Traverses the octree and insert for each leaf the getSurface-function into the thread pool.
| mesh | The reconstructed mesh. | 
| node | Actually node. | 
| 
 | protected | 
Definition at line 264 of file DMCReconstruction.hpp.
| 
 | protected | 
Definition at line 262 of file DMCReconstruction.hpp.
| 
 | protected | 
Definition at line 261 of file DMCReconstruction.hpp.
| 
 | protected | 
Definition at line 263 of file DMCReconstruction.hpp.
| 
 | protected | 
Definition at line 282 of file DMCReconstruction.hpp.
| 
 | protected | 
Definition at line 267 of file DMCReconstruction.hpp.
| 
 | protected | 
Definition at line 252 of file DMCReconstruction.hpp.
| 
 | protected | 
Definition at line 270 of file DMCReconstruction.hpp.
| 
 | protected | 
Definition at line 258 of file DMCReconstruction.hpp.
| 
 | protected | 
Definition at line 255 of file DMCReconstruction.hpp.
| 
 | protected | 
Definition at line 279 of file DMCReconstruction.hpp.
| 
 | protected | 
Definition at line 273 of file DMCReconstruction.hpp.
| 
 | protected | 
Definition at line 276 of file DMCReconstruction.hpp.