Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
lvr2::DMCReconstruction< BaseVecT, BoxT > Class Template Reference

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>

Inheritance diagram for lvr2::DMCReconstruction< BaseVecT, BoxT >:
Inheritance graph
[legend]

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
 
ProgressBarm_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...
 

Detailed Description

template<typename BaseVecT, typename BoxT>
class lvr2::DMCReconstruction< BaseVecT, BoxT >

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.

Constructor & Destructor Documentation

◆ DMCReconstruction()

template<typename BaseVecT , typename BoxT >
lvr2::DMCReconstruction< BaseVecT, BoxT >::DMCReconstruction ( PointsetSurfacePtr< BaseVecT >  surface,
BoundingBox< BaseVecT >  bb,
bool  dual,
int  maxLevel,
float  maxError 
)

Constructor.

Parameters
surfacePointer to the surface
bbBoundingBox of the PointCloud
dual
maxLevelMax allowed octree level
maxErrorMax allowed error between points and surfaces

◆ ~DMCReconstruction()

template<typename BaseVecT , typename BoxT >
virtual lvr2::DMCReconstruction< BaseVecT, BoxT >::~DMCReconstruction ( )
virtual

Destructor.

Member Function Documentation

◆ buildTree()

template<typename BaseVecT , typename BoxT >
void lvr2::DMCReconstruction< BaseVecT, BoxT >::buildTree ( C_Octree< BaseVecT, BoxT, my_dummy > &  parent,
int  levels,
bool  dual 
)
protected

Builds a tree level respectively creates the child nodes of a root node.

Parameters
parentPointsPoints inside the parent node.
parentReference to the parent node.
childCenterCenters of the children.
sizeActually voxelsize.
parentCenterCenter of the parent node.

◆ detectVertexForDualCell()

template<typename BaseVecT , typename BoxT >
void lvr2::DMCReconstruction< BaseVecT, BoxT >::detectVertexForDualCell ( C_Octree< BaseVecT, BoxT, my_dummy > &  octree,
CellHandle  ch,
int  cells,
float  max_bb_width,
uint  pos,
int  onEdge,
BaseVecT &  feature 
)
protected

Calculates the position of a aspecific point in a dual cell.

Parameters
octreeThe current octree instace
chThe current cellHandle of the octree
cellsNumber of possible cells at current level
max_bb_widthWidth of the bounding box
posPosition of the dual cell relative to the given cell
onEdgeIndicator whether the wished position lies on an edge
featureVector that should be filles with the correct position

◆ drawOctree()

template<typename BaseVecT , typename BoxT >
void lvr2::DMCReconstruction< BaseVecT, BoxT >::drawOctree ( C_Octree< BaseVecT, BoxT, my_dummy > &  parent)
protected

Saves the octree as wireframe. WORKS ONLY SINGLE THREADED!

Parameters
parentThe octree

◆ edgeEquation()

template<typename BaseVecT , typename BoxT >
float lvr2::DMCReconstruction< BaseVecT, BoxT >::edgeEquation ( BaseVecT  p,
BaseVecT  v1,
BaseVecT  v2 
)
protected

Calculates whether the given vertex lies left, right or on the given line.

Parameters
pVertex to check position for
v1First point of the line
v2Second point of the line

◆ getDistance() [1/3]

template<typename BaseVecT , typename BoxT >
float lvr2::DMCReconstruction< BaseVecT, BoxT >::getDistance ( BaseVecT  p,
BaseVecT  v1,
BaseVecT  v2 
)
protected

Calculates the distance between a point and a line.

Parameters
pVertex to calculate distance for
v1First point of the line
v2Second point of the line

◆ getDistance() [2/3]

template<typename BaseVecT , typename BoxT >
float lvr2::DMCReconstruction< BaseVecT, BoxT >::getDistance ( BaseVecT  p,
BaseVecT  v1,
BaseVecT  v2,
BaseVecT  v3 
)
protected

Calculates the distance between a point and a triangle.

Parameters
pVertex to calculate distance for
v1First point of the triangle
v2Second point of the triangle
v3Third point of the triangle

◆ getDistance() [3/3]

template<typename BaseVecT , typename BoxT >
float lvr2::DMCReconstruction< BaseVecT, BoxT >::getDistance ( BaseVecT  v1,
BaseVecT  v2 
)
protected

Calculates the distance between to points.

Parameters
pVertex to calculate distance for
v1Point

◆ getDualLeaf()

template<typename BaseVecT , typename BoxT >
DualLeaf<BaseVecT, BoxT>* lvr2::DMCReconstruction< BaseVecT, BoxT >::getDualLeaf ( CellHandle cell,
int  cells,
C_Octree< BaseVecT, BoxT, my_dummy > &  octree,
char  pos 
)
protected

Builds a dual cell at given position.

Parameters
cellCell of the regual octree
cellsnumber of cells at the cells octree level
octreeReference to the octree
posPosition of the specific dual cell

◆ getMesh() [1/2]

template<typename BaseVecT , typename BoxT >
virtual void lvr2::DMCReconstruction< BaseVecT, BoxT >::getMesh ( BaseMesh< BaseVecT > &  mesh)
virtual

Returns the surface reconstruction of the given point set.

Parameters
mesh

Implements lvr2::FastReconstructionBase< BaseVecT >.

◆ getMesh() [2/2]

template<typename BaseVecT , typename BoxT >
virtual void lvr2::DMCReconstruction< BaseVecT, BoxT >::getMesh ( BaseMesh< BaseVecT > &  mesh,
BoundingBox< BaseVecT > &  bb,
vector< unsigned int > &  duplicates,
float  comparePrecision 
)
virtual

◆ getRotationMatrix()

template<typename BaseVecT , typename BoxT >
void lvr2::DMCReconstruction< BaseVecT, BoxT >::getRotationMatrix ( float  matrix[9],
BaseVecT  v1,
BaseVecT  v2,
BaseVecT  v3 
)
protected

Calculates a rotation matrix for a triangle that rotates it into xy.

Parameters
matrixArray the matrix should be written in
v1First point of the triangle
v2Second point of the triangle
v3Third point of the triangle

◆ getSurface()

template<typename BaseVecT , typename BoxT >
void lvr2::DMCReconstruction< BaseVecT, BoxT >::getSurface ( BaseMesh< BaseVecT > &  mesh,
DualLeaf< BaseVecT, BoxT > *  leaf,
int  cells,
short  level 
)
protected

Performs a local reconstruction according to the standard Marching Cubes table from Paul Bourke.

Parameters
meshThe reconstructed mesh
leafA octree leaf.
cells

◆ matrixDotVector()

template<typename BaseVecT , typename BoxT >
void lvr2::DMCReconstruction< BaseVecT, BoxT >::matrixDotVector ( float *  matrix,
BaseVecT *  vector 
)
protected

Performs a matrix multiplication.

Parameters
matrixPointer to the matrix
vectorPointer to th vector

◆ traverseTree()

template<typename BaseVecT , typename BoxT >
void lvr2::DMCReconstruction< BaseVecT, BoxT >::traverseTree ( BaseMesh< BaseVecT > &  mesh,
C_Octree< BaseVecT, BoxT, my_dummy > &  octree 
)
protected

Traverses the octree and insert for each leaf the getSurface-function into the thread pool.

Parameters
meshThe reconstructed mesh.
nodeActually node.

Member Data Documentation

◆ bb_longestSide

template<typename BaseVecT , typename BoxT >
float lvr2::DMCReconstruction< BaseVecT, BoxT >::bb_longestSide
protected

Definition at line 264 of file DMCReconstruction.hpp.

◆ bb_max

template<typename BaseVecT , typename BoxT >
BaseVecT lvr2::DMCReconstruction< BaseVecT, BoxT >::bb_max
protected

Definition at line 262 of file DMCReconstruction.hpp.

◆ bb_min

template<typename BaseVecT , typename BoxT >
BaseVecT lvr2::DMCReconstruction< BaseVecT, BoxT >::bb_min
protected

Definition at line 261 of file DMCReconstruction.hpp.

◆ bb_size

template<typename BaseVecT , typename BoxT >
float lvr2::DMCReconstruction< BaseVecT, BoxT >::bb_size[3]
protected

Definition at line 263 of file DMCReconstruction.hpp.

◆ dualVertices

template<typename BaseVecT , typename BoxT >
std::vector< BaseVecT > lvr2::DMCReconstruction< BaseVecT, BoxT >::dualVertices
protected

Definition at line 282 of file DMCReconstruction.hpp.

◆ m_boundingBoxCenter

template<typename BaseVecT , typename BoxT >
BaseVecT lvr2::DMCReconstruction< BaseVecT, BoxT >::m_boundingBoxCenter
protected

Definition at line 267 of file DMCReconstruction.hpp.

◆ m_dual

template<typename BaseVecT , typename BoxT >
bool lvr2::DMCReconstruction< BaseVecT, BoxT >::m_dual
protected

Definition at line 252 of file DMCReconstruction.hpp.

◆ m_leaves

template<typename BaseVecT , typename BoxT >
uint lvr2::DMCReconstruction< BaseVecT, BoxT >::m_leaves
protected

Definition at line 270 of file DMCReconstruction.hpp.

◆ m_maxError

template<typename BaseVecT , typename BoxT >
float lvr2::DMCReconstruction< BaseVecT, BoxT >::m_maxError
protected

Definition at line 258 of file DMCReconstruction.hpp.

◆ m_maxLevel

template<typename BaseVecT , typename BoxT >
int lvr2::DMCReconstruction< BaseVecT, BoxT >::m_maxLevel
protected

Definition at line 255 of file DMCReconstruction.hpp.

◆ m_pointHandler

template<typename BaseVecT , typename BoxT >
unique_ptr<DMCPointHandle<BaseVecT> > lvr2::DMCReconstruction< BaseVecT, BoxT >::m_pointHandler
protected

Definition at line 279 of file DMCReconstruction.hpp.

◆ m_progressBar

template<typename BaseVecT , typename BoxT >
ProgressBar* lvr2::DMCReconstruction< BaseVecT, BoxT >::m_progressBar
protected

Definition at line 273 of file DMCReconstruction.hpp.

◆ octree

template<typename BaseVecT , typename BoxT >
C_Octree<BaseVecT, BoxT, my_dummy>* lvr2::DMCReconstruction< BaseVecT, BoxT >::octree
protected

Definition at line 276 of file DMCReconstruction.hpp.


The documentation for this class was generated from the following file:


lvr2
Author(s): Thomas Wiemann , Sebastian Pütz , Alexander Mock , Lars Kiesow , Lukas Kalbertodt , Tristan Igelbrink , Johan M. von Behren , Dominik Feldschnieders , Alexander Löhr
autogenerated on Wed Mar 2 2022 00:37:27