Public Member Functions | Private Member Functions | Private Attributes | List of all members
lvr2::GrowingCellStructure< BaseVecT, NormalT > Class Template Reference

#include <GrowingCellStructure.hpp>

Public Member Functions

int getAllowMiss () const
 
int getBasicSteps () const
 
float getBoxFactor () const
 
float getCollapseThreshold () const
 
float getDecreaseFactor () const
 
int getDeleteLongEdgesFactor () const
 
float getLearningRate () const
 
void getMesh (HalfEdgeMesh< BaseVecT > &mesh)
 
float getNeighborLearningRate () const
 
int getNumSplits () const
 
int getRuntime () const
 
 GrowingCellStructure (PointsetSurfacePtr< BaseVecT > &surface)
 
bool isFilterChain () const
 
bool isInterior () const
 
bool isWithCollapse () const
 
void setAllowMiss (int m_allowMiss)
 
void setBasicSteps (int m_basicSteps)
 
void setBoxFactor (float m_boxFactor)
 
void setCollapseThreshold (float m_collapseThreshold)
 
void setDecreaseFactor (float m_decreaseFactor)
 
void setDeleteLongEdgesFactor (int m_deleteLongEdgesFactor)
 
void setFilterChain (bool m_filterChain)
 
void setInterior (bool m_interior)
 
void setLearningRate (float m_learningRate)
 
void setNeighborLearningRate (float m_neighborLearningRate)
 
void setNumBalances (int m_balances)
 
void setNumSplits (int m_numSplits)
 
void setRuntime (int m_runtime)
 
void setWithCollapse (bool m_withCollapse)
 

Private Member Functions

void aggressiveCutOut (VertexHandle vH)
 
double avgDistanceBetweenPointsInPointcloud ()
 
double avgValence ()
 
int cellVecSize ()
 
std::pair< double, double > equilaterality ()
 
void executeBasicStep (PacmanProgressBar &progress_bar)
 
void executeEdgeCollapse ()
 
void executeVertexSplit ()
 
VertexHandle getClosestPointInMesh (BaseVecT point, PacmanProgressBar &progress_bar)
 
void getInitialMesh ()
 
BaseVecT getRandomPointFromPointcloud ()
 
void initTestMesh ()
 
int numVertexValences (int minValence)
 
void performLaplacianSmoothing (VertexHandle vertexH, BaseVecT random, float factor=0.01)
 
void removeWrongFaces ()
 

Private Attributes

std::vector< Cell * > cellArr
 
HashMap< FaceHandle, std::pair< float, float > > faceAgeErrorMap
 
int flipCounter = 0
 
DynamicKDTree< BaseVecT > * kd_tree
 
int m_allowMiss
 
float m_avgEdgeLength = 0
 
float m_avgFaceSize = 0
 
float m_avgSignalCounter = 0
 
int m_balances
 
int m_basicSteps
 
float m_boxFactor
 
float m_collapseThreshold
 
float m_decreaseFactor
 
int m_deleteLongEdgesFactor
 
bool m_filterChain
 
bool m_interior
 
float m_learningRate
 
float m_limSingle
 
float m_limSkip
 
float m_maxAge
 
HalfEdgeMesh< BaseVecT > * m_mesh
 
float m_neighborLearningRate
 
int m_numSplits
 
int m_runtime
 
PointsetSurfacePtr< BaseVecT > * m_surface
 
bool m_useGSS = false
 
bool m_withCollapse
 
bool m_withRemove
 
int notFoundCounter = 0
 
TumbleTreetumble_tree
 

Detailed Description

template<typename BaseVecT, typename NormalT>
class lvr2::GrowingCellStructure< BaseVecT, NormalT >

Definition at line 19 of file GrowingCellStructure.hpp.

Constructor & Destructor Documentation

◆ GrowingCellStructure()

template<typename BaseVecT , typename NormalT >
lvr2::GrowingCellStructure< BaseVecT, NormalT >::GrowingCellStructure ( PointsetSurfacePtr< BaseVecT > &  surface)

Construct a GCS instance

Parameters
surfacepointsetsurface to get pointcloud information from

Member Function Documentation

◆ aggressiveCutOut()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::aggressiveCutOut ( VertexHandle  vH)
private

◆ avgDistanceBetweenPointsInPointcloud()

template<typename BaseVecT , typename NormalT >
double lvr2::GrowingCellStructure< BaseVecT, NormalT >::avgDistanceBetweenPointsInPointcloud ( )
private

◆ avgValence()

template<typename BaseVecT , typename NormalT >
double lvr2::GrowingCellStructure< BaseVecT, NormalT >::avgValence ( )
private

◆ cellVecSize()

template<typename BaseVecT , typename NormalT >
int lvr2::GrowingCellStructure< BaseVecT, NormalT >::cellVecSize ( )
private

◆ equilaterality()

template<typename BaseVecT , typename NormalT >
std::pair<double, double> lvr2::GrowingCellStructure< BaseVecT, NormalT >::equilaterality ( )
private

◆ executeBasicStep()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::executeBasicStep ( PacmanProgressBar progress_bar)
private

◆ executeEdgeCollapse()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::executeEdgeCollapse ( )
private

◆ executeVertexSplit()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::executeVertexSplit ( )
private

◆ getAllowMiss()

template<typename BaseVecT , typename NormalT >
int lvr2::GrowingCellStructure< BaseVecT, NormalT >::getAllowMiss ( ) const
inline

Definition at line 51 of file GrowingCellStructure.hpp.

◆ getBasicSteps()

template<typename BaseVecT , typename NormalT >
int lvr2::GrowingCellStructure< BaseVecT, NormalT >::getBasicSteps ( ) const
inline

Definition at line 37 of file GrowingCellStructure.hpp.

◆ getBoxFactor()

template<typename BaseVecT , typename NormalT >
float lvr2::GrowingCellStructure< BaseVecT, NormalT >::getBoxFactor ( ) const
inline

Definition at line 41 of file GrowingCellStructure.hpp.

◆ getClosestPointInMesh()

template<typename BaseVecT , typename NormalT >
VertexHandle lvr2::GrowingCellStructure< BaseVecT, NormalT >::getClosestPointInMesh ( BaseVecT  point,
PacmanProgressBar progress_bar 
)
private

◆ getCollapseThreshold()

template<typename BaseVecT , typename NormalT >
float lvr2::GrowingCellStructure< BaseVecT, NormalT >::getCollapseThreshold ( ) const
inline

Definition at line 53 of file GrowingCellStructure.hpp.

◆ getDecreaseFactor()

template<typename BaseVecT , typename NormalT >
float lvr2::GrowingCellStructure< BaseVecT, NormalT >::getDecreaseFactor ( ) const
inline

Definition at line 49 of file GrowingCellStructure.hpp.

◆ getDeleteLongEdgesFactor()

template<typename BaseVecT , typename NormalT >
int lvr2::GrowingCellStructure< BaseVecT, NormalT >::getDeleteLongEdgesFactor ( ) const
inline

Definition at line 57 of file GrowingCellStructure.hpp.

◆ getInitialMesh()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::getInitialMesh ( )
private

◆ getLearningRate()

template<typename BaseVecT , typename NormalT >
float lvr2::GrowingCellStructure< BaseVecT, NormalT >::getLearningRate ( ) const
inline

Definition at line 45 of file GrowingCellStructure.hpp.

◆ getMesh()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::getMesh ( HalfEdgeMesh< BaseVecT > &  mesh)

Public method of the Reconstruction Class, calling all the other methods, generating the mesh approximating the pointcloud's surface

Parameters
meshpointer to the mesh

◆ getNeighborLearningRate()

template<typename BaseVecT , typename NormalT >
float lvr2::GrowingCellStructure< BaseVecT, NormalT >::getNeighborLearningRate ( ) const
inline

Definition at line 47 of file GrowingCellStructure.hpp.

◆ getNumSplits()

template<typename BaseVecT , typename NormalT >
int lvr2::GrowingCellStructure< BaseVecT, NormalT >::getNumSplits ( ) const
inline

Definition at line 39 of file GrowingCellStructure.hpp.

◆ getRandomPointFromPointcloud()

template<typename BaseVecT , typename NormalT >
BaseVecT lvr2::GrowingCellStructure< BaseVecT, NormalT >::getRandomPointFromPointcloud ( )
private

◆ getRuntime()

template<typename BaseVecT , typename NormalT >
int lvr2::GrowingCellStructure< BaseVecT, NormalT >::getRuntime ( ) const
inline

Definition at line 35 of file GrowingCellStructure.hpp.

◆ initTestMesh()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::initTestMesh ( )
private

◆ isFilterChain()

template<typename BaseVecT , typename NormalT >
bool lvr2::GrowingCellStructure< BaseVecT, NormalT >::isFilterChain ( ) const
inline

Definition at line 55 of file GrowingCellStructure.hpp.

◆ isInterior()

template<typename BaseVecT , typename NormalT >
bool lvr2::GrowingCellStructure< BaseVecT, NormalT >::isInterior ( ) const
inline

Definition at line 59 of file GrowingCellStructure.hpp.

◆ isWithCollapse()

template<typename BaseVecT , typename NormalT >
bool lvr2::GrowingCellStructure< BaseVecT, NormalT >::isWithCollapse ( ) const
inline

Definition at line 43 of file GrowingCellStructure.hpp.

◆ numVertexValences()

template<typename BaseVecT , typename NormalT >
int lvr2::GrowingCellStructure< BaseVecT, NormalT >::numVertexValences ( int  minValence)
private

◆ performLaplacianSmoothing()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::performLaplacianSmoothing ( VertexHandle  vertexH,
BaseVecT  random,
float  factor = 0.01 
)
private

◆ removeWrongFaces()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::removeWrongFaces ( )
private

◆ setAllowMiss()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::setAllowMiss ( int  m_allowMiss)
inline

Definition at line 89 of file GrowingCellStructure.hpp.

◆ setBasicSteps()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::setBasicSteps ( int  m_basicSteps)
inline

Definition at line 63 of file GrowingCellStructure.hpp.

◆ setBoxFactor()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::setBoxFactor ( float  m_boxFactor)
inline

Definition at line 67 of file GrowingCellStructure.hpp.

◆ setCollapseThreshold()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::setCollapseThreshold ( float  m_collapseThreshold)
inline

Definition at line 91 of file GrowingCellStructure.hpp.

◆ setDecreaseFactor()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::setDecreaseFactor ( float  m_decreaseFactor)
inline

Definition at line 84 of file GrowingCellStructure.hpp.

◆ setDeleteLongEdgesFactor()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::setDeleteLongEdgesFactor ( int  m_deleteLongEdgesFactor)
inline

Definition at line 98 of file GrowingCellStructure.hpp.

◆ setFilterChain()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::setFilterChain ( bool  m_filterChain)
inline

Definition at line 96 of file GrowingCellStructure.hpp.

◆ setInterior()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::setInterior ( bool  m_interior)
inline

Definition at line 103 of file GrowingCellStructure.hpp.

◆ setLearningRate()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::setLearningRate ( float  m_learningRate)
inline

Definition at line 74 of file GrowingCellStructure.hpp.

◆ setNeighborLearningRate()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::setNeighborLearningRate ( float  m_neighborLearningRate)
inline

Definition at line 79 of file GrowingCellStructure.hpp.

◆ setNumBalances()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::setNumBalances ( int  m_balances)
inline

Definition at line 105 of file GrowingCellStructure.hpp.

◆ setNumSplits()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::setNumSplits ( int  m_numSplits)
inline

Definition at line 65 of file GrowingCellStructure.hpp.

◆ setRuntime()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::setRuntime ( int  m_runtime)
inline

Definition at line 61 of file GrowingCellStructure.hpp.

◆ setWithCollapse()

template<typename BaseVecT , typename NormalT >
void lvr2::GrowingCellStructure< BaseVecT, NormalT >::setWithCollapse ( bool  m_withCollapse)
inline

Definition at line 69 of file GrowingCellStructure.hpp.

Member Data Documentation

◆ cellArr

template<typename BaseVecT , typename NormalT >
std::vector<Cell*> lvr2::GrowingCellStructure< BaseVecT, NormalT >::cellArr
private

Definition at line 127 of file GrowingCellStructure.hpp.

◆ faceAgeErrorMap

template<typename BaseVecT , typename NormalT >
HashMap<FaceHandle, std::pair<float, float> > lvr2::GrowingCellStructure< BaseVecT, NormalT >::faceAgeErrorMap
private

Definition at line 140 of file GrowingCellStructure.hpp.

◆ flipCounter

template<typename BaseVecT , typename NormalT >
int lvr2::GrowingCellStructure< BaseVecT, NormalT >::flipCounter = 0
private

Definition at line 135 of file GrowingCellStructure.hpp.

◆ kd_tree

template<typename BaseVecT , typename NormalT >
DynamicKDTree<BaseVecT>* lvr2::GrowingCellStructure< BaseVecT, NormalT >::kd_tree
private

Definition at line 126 of file GrowingCellStructure.hpp.

◆ m_allowMiss

template<typename BaseVecT , typename NormalT >
int lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_allowMiss
private

Definition at line 131 of file GrowingCellStructure.hpp.

◆ m_avgEdgeLength

template<typename BaseVecT , typename NormalT >
float lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_avgEdgeLength = 0
private

Definition at line 142 of file GrowingCellStructure.hpp.

◆ m_avgFaceSize

template<typename BaseVecT , typename NormalT >
float lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_avgFaceSize = 0
private

Definition at line 141 of file GrowingCellStructure.hpp.

◆ m_avgSignalCounter

template<typename BaseVecT , typename NormalT >
float lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_avgSignalCounter = 0
private

Definition at line 122 of file GrowingCellStructure.hpp.

◆ m_balances

template<typename BaseVecT , typename NormalT >
int lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_balances
private

Definition at line 121 of file GrowingCellStructure.hpp.

◆ m_basicSteps

template<typename BaseVecT , typename NormalT >
int lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_basicSteps
private

Definition at line 113 of file GrowingCellStructure.hpp.

◆ m_boxFactor

template<typename BaseVecT , typename NormalT >
float lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_boxFactor
private

Definition at line 115 of file GrowingCellStructure.hpp.

◆ m_collapseThreshold

template<typename BaseVecT , typename NormalT >
float lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_collapseThreshold
private

Definition at line 132 of file GrowingCellStructure.hpp.

◆ m_decreaseFactor

template<typename BaseVecT , typename NormalT >
float lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_decreaseFactor
private

Definition at line 130 of file GrowingCellStructure.hpp.

◆ m_deleteLongEdgesFactor

template<typename BaseVecT , typename NormalT >
int lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_deleteLongEdgesFactor
private

Definition at line 133 of file GrowingCellStructure.hpp.

◆ m_filterChain

template<typename BaseVecT , typename NormalT >
bool lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_filterChain
private

Definition at line 119 of file GrowingCellStructure.hpp.

◆ m_interior

template<typename BaseVecT , typename NormalT >
bool lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_interior
private

Definition at line 120 of file GrowingCellStructure.hpp.

◆ m_learningRate

template<typename BaseVecT , typename NormalT >
float lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_learningRate
private

Definition at line 117 of file GrowingCellStructure.hpp.

◆ m_limSingle

template<typename BaseVecT , typename NormalT >
float lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_limSingle
private

Definition at line 145 of file GrowingCellStructure.hpp.

◆ m_limSkip

template<typename BaseVecT , typename NormalT >
float lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_limSkip
private

Definition at line 144 of file GrowingCellStructure.hpp.

◆ m_maxAge

template<typename BaseVecT , typename NormalT >
float lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_maxAge
private

Definition at line 146 of file GrowingCellStructure.hpp.

◆ m_mesh

template<typename BaseVecT , typename NormalT >
HalfEdgeMesh<BaseVecT>* lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_mesh
private

Definition at line 109 of file GrowingCellStructure.hpp.

◆ m_neighborLearningRate

template<typename BaseVecT , typename NormalT >
float lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_neighborLearningRate
private

Definition at line 118 of file GrowingCellStructure.hpp.

◆ m_numSplits

template<typename BaseVecT , typename NormalT >
int lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_numSplits
private

Definition at line 114 of file GrowingCellStructure.hpp.

◆ m_runtime

template<typename BaseVecT , typename NormalT >
int lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_runtime
private

Definition at line 112 of file GrowingCellStructure.hpp.

◆ m_surface

template<typename BaseVecT , typename NormalT >
PointsetSurfacePtr<BaseVecT>* lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_surface
private

Definition at line 108 of file GrowingCellStructure.hpp.

◆ m_useGSS

template<typename BaseVecT , typename NormalT >
bool lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_useGSS = false
private

Definition at line 138 of file GrowingCellStructure.hpp.

◆ m_withCollapse

template<typename BaseVecT , typename NormalT >
bool lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_withCollapse
private

Definition at line 116 of file GrowingCellStructure.hpp.

◆ m_withRemove

template<typename BaseVecT , typename NormalT >
bool lvr2::GrowingCellStructure< BaseVecT, NormalT >::m_withRemove
private

Definition at line 147 of file GrowingCellStructure.hpp.

◆ notFoundCounter

template<typename BaseVecT , typename NormalT >
int lvr2::GrowingCellStructure< BaseVecT, NormalT >::notFoundCounter = 0
private

Definition at line 134 of file GrowingCellStructure.hpp.

◆ tumble_tree

template<typename BaseVecT , typename NormalT >
TumbleTree* lvr2::GrowingCellStructure< BaseVecT, NormalT >::tumble_tree
private

Definition at line 125 of file GrowingCellStructure.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