Public Member Functions | Private Attributes | List of all members
LargeScaleOptions::Options Class Reference

A class to parse the program options for the reconstruction executable. More...

#include <LargeScaleOptions.hpp>

Inheritance diagram for LargeScaleOptions::Options:
Inheritance graph
[legend]

Public Member Functions

bool clusterPlanes () const
 True if region clustering without plane optimization is required. More...
 
bool colorRegions () const
 Returns true of region coloring is enabled. More...
 
bool doTextureAnalysis () const
 True if texture analysis is enabled. More...
 
bool extrude () const
 Whether to extend the grid. Enabled by default. More...
 
bool filenameSet () const
 Returns true if an output filen name was set. More...
 
bool generateTextures () const
 If true, textures will be generated during finalization of mesh. More...
 
float getBGVoxelsize () const
 Returns the given voxelsize for bigGrid. More...
 
bool getBigMesh () const
 Returns if the new chunks should be written as a .ply-mesh. More...
 
unsigned int getBufferSize () const
 
int getChunkSize () const
 Returns the chunksize. More...
 
string getClassifier () const
 Returns the name of the classifier used to color the mesh. More...
 
int getCleanContourIterations () const
 Number of iterations for contour cleanup. More...
 
unsigned int getCoherenceThreshold () const
 
float getColorThreshold () const
 
int getDanglingArtifacts () const
 Returns the number of dangling artifacts to remove from a created mesh. More...
 
bool getDebugChunks () const
 Returns if the mesh of every chunk additionally should be written as a .ply. More...
 
string getDecomposition () const
 Returns the name of the used point cloud handler. More...
 
int getDepth () const
 Returns the maximum recursion depth for region growing. More...
 
string getEdgeCollapseMethod () const
 Edge collapse method. More...
 
float getFeatureThreshold () const
 
int getFillHoles () const
 Returns the region threshold for hole filling. More...
 
vector< float > getFlippoint () const
 Returns the flipPoint for GPU normal computation. More...
 
std::vector< string > getInputFileName () const
 Returns the output file name. More...
 
int getIntersections () const
 Returns the number of intersections. If the return value is positive it will be used for reconstruction instead of absolute voxelsize. More...
 
int getKd () const
 Returns the number of neighbors used for distance function evaluation. More...
 
int getKi () const
 Returns the number of neighbors for normal interpolation. More...
 
int getKn () const
 Returns the number of neighbors used for initial normal estimation. More...
 
float getLineFusionThreshold () const
 Returns the fusion threshold for tesselation. More...
 
size_t getLineReaderBuffer () const
 
int getMinimumTransformationVotes () const
 
int getMinPlaneSize () const
 Minimum value for plane optimzation. More...
 
unsigned int getNodeSize () const
 Only used in kd-tree (partMethod=0). Returns the maximum number of points in a leaf. More...
 
float getNormalThreshold () const
 Returns the normal threshold for plane optimization. More...
 
unsigned int getNumCCVColors () const
 
int getNumEdgeCollapses () const
 Number of edge collapses. More...
 
unsigned int getNumStatsColors () const
 
int getNumThreads () const
 Returns the number of used threads. More...
 
string getOutputFolderPath () const
 
int getPartMethod () const
 Retuns flag for partition-method (0 = kd-Tree; 1 = VGrid) More...
 
float getPatternThreshold () const
 
string getPCM () const
 Returns the name of the used point cloud handler. More...
 
int getPlaneIterations () const
 Returns to number plane optimization iterations. More...
 
float getScaling () const
 Returns the scaling factor. More...
 
string getScanPoseFile () const
 Returns the name of the given file with scan poses used for normal flipping. More...
 
float getSharpCornerThreshold () const
 Returns the sharp corner threshold when using sharp feature decomposition. More...
 
float getSharpFeatureThreshold () const
 Returns the sharp feature threshold when using sharp feature decomposition. More...
 
int getSmallRegionThreshold () const
 Returns the threshold for the size of small region deletion after plane optimization. More...
 
float * getStatsCoeffs () const
 
float getStatsThreshold () const
 
float getTexelSize () const
 Returns the texel size for texture resolution. More...
 
string getTexturePack () const
 
bool getUseCrossCorr () const
 
bool getUseNormals () const
 
size_t getVolumenSize () const
 
float getVoxelsize () const
 Returns the first given voxelsize. More...
 
vector< float > getVoxelSizes () const
 Returns all voxelsizes as a vector. More...
 
bool interpolateBoxes () const
 
bool onlyNormals () const
 
bool optimizePlanes () const
 Returns true if cluster optimization is enabled. More...
 
 Options (int argc, char **argv)
 Ctor. Parses the command parameters given to the main function of the program. More...
 
bool printUsage () const
 Prints a usage message to stdout. More...
 
bool recalcNormals () const
 If true, normals should be calculated even if they are already given in the input file. More...
 
bool retesselate () const
 Return whether the mesh should be retesselated or not. More...
 
bool saveFaceNormals () const
 Returns true if the face normals of the reconstructed mesh should be saved to an extra file ("face_normals.nor") More...
 
bool saveGrid () const
 Returns true if the Marching Cubes grid should be save. More...
 
bool saveNormals () const
 Returns true if the interpolated normals should be saved in the putput file. More...
 
bool saveOriginalData () const
 Returns true if the original points should be stored together with the reconstruction. More...
 
bool savePointNormals () const
 Indicates whether to save the used points together with the interpolated normals. More...
 
bool useGPU () const
 Returns if the GPU shuold be used for the normal estimation. More...
 
bool useRansac () const
 If true, RANSAC based normal estimation is used. More...
 
bool writeClassificationResult () const
 True if region clustering without plane optimization is required. More...
 
virtual ~Options ()
 
- Public Member Functions inherited from lvr2::BaseOption
 BaseOption (int argc, char **argv)
 
CoordinateTransform< float > coordinateTransform () const
 
void printLogo () const
 
void printTransformation (std::ostream &out) const
 Prints transformation information to the given output stream. More...
 
float sx () const
 Returns the scaling factor for the x coordinates. More...
 
float sy () const
 Returns the scaling factor for the y coordinates. More...
 
float sz () const
 Returns the scaling factor for the z coordinates. More...
 
int x () const
 Returns the position of the x coordinate in the data. More...
 
int y () const
 Returns the position of the x coordinate in the data. More...
 
int z () const
 Returns the position of the x coordinate in the data. More...
 
virtual ~BaseOption ()
 

Private Attributes

bool m_bigMesh
 flag to generate a .ply file for the reconstructed mesh More...
 
unsigned int m_bufferSize
 
int m_chunkSize
 gridsize for virtual grid More...
 
string m_classifier
 Name of the classifier object to color the mesh. More...
 
int m_cleanContourIterations
 number of cleanContour iterations More...
 
unsigned int m_coherenceThreshold
 Coherence threshold for texture matching based on color information. More...
 
float m_colorThreshold
 Threshold for texture matching based on colors. More...
 
bool m_debugChunks
 flag to generate debug meshes for every chunk as a .ply More...
 
int m_depth
 Maximum recursion depth for region growing. More...
 
string m_ecm
 Edge collapse method. More...
 
bool m_extrude
 extruded flag More...
 
string m_faceNormalFile
 The putput file name for face normals. More...
 
float m_featuresThreshold
 Threshold for texture matching based on features. More...
 
int m_fillHoles
 Threshold for hole filling. More...
 
vector< float > m_flippoint
 flipPoint for GPU normal computation More...
 
bool m_generateTextures
 Whether or not the mesh should be retesselated while being finalized. More...
 
bool m_interpolateBoxes
 
int m_intersections
 The number of intersections used for reconstruction. More...
 
int m_kd
 The number of neighbors for distance function evaluation. More...
 
int m_ki
 The number of neighbors for normal interpolation. More...
 
int m_kn
 The number of neighbors for normal estimation. More...
 
float m_lineFusionThreshold
 Threshold for line fusing when tesselating. More...
 
size_t m_lineReaderBuffer
 
int m_minimumTransformationVotes
 Minimum number of vote to consider a texture transformation as "correct". More...
 
int m_minPlaneSize
 Threshold for plane optimization. More...
 
int m_numberOfDefaults
 The number of used default values. More...
 
unsigned int m_numCCVColors
 Number of colors for texture matching based on color information. More...
 
int m_numEdgeCollapses
 Number of edge collapses. More...
 
unsigned int m_numStatsColors
 Number of colors for texture statistics. More...
 
int m_numThreads
 The number of used threads. More...
 
unsigned int m_octreeNodeSize
 
bool m_onlyNormals
 
string m_outputFolderPath
 
int m_partMethod
 sets partition method to kd-tree or virtual grid More...
 
float m_patternThreshold
 Threshold for pattern extraction from textures. More...
 
string m_pcm
 The used point cloud manager. More...
 
int m_planeIterations
 Number of iterations for plane optimzation. More...
 
float m_planeNormalThreshold
 Threshold for plane optimization. More...
 
int m_removeDanglingArtifacts
 Number of dangling artifacts to remove. More...
 
bool m_retesselate
 Whether or not the mesh should be retesselated while being finalized. More...
 
float m_scaling
 
float m_sct
 Sharp corner threshold when using sharp feature decomposition. More...
 
float m_sft
 Sharp feature threshold when using sharp feature decomposition. More...
 
int m_smallRegionThreshold
 Threshold for small regions. More...
 
string m_statsCoeffs
 Coefficents file for texture matching based on statistics. More...
 
float m_statsThreshold
 Threshold for texture matching based on statistics. More...
 
float m_texelSize
 Texel size. More...
 
string m_texturePack
 Path to texture pack. More...
 
bool m_use_normals
 
bool m_useCrossCorr
 Whether to use texture matching based on cross correlation. More...
 
size_t m_volumenSize
 
float m_voxelsize
 The set voxelsize. More...
 
float m_voxelsizeBG
 The set voxelsize for BigGrid. More...
 
vector< float > m_voxelSizes
 The set voxelsizes. More...
 
bool m_writeClassificationResult
 Whether or not the classifier shall dump meta data to a file 'clusters.clu'. More...
 

Additional Inherited Members

- Protected Member Functions inherited from lvr2::BaseOption
virtual void setup ()
 Setup internal data structures. More...
 
void setupInputTransformation ()
 Setup transformation info for ModelIO. More...
 
- Protected Attributes inherited from lvr2::BaseOption
int m_argc
 Argument count. More...
 
char ** m_argv
 Argument values. More...
 
CoordinateTransform< float > * m_coordinateTransform
 Coordinate transform information. More...
 
options_description m_descr
 The internally used option description. More...
 
positional_options_description m_pdescr
 The internally used positional option desription. More...
 
variables_map m_variables
 The internally used variable map. More...
 

Detailed Description

A class to parse the program options for the reconstruction executable.

Definition at line 58 of file LargeScaleOptions.hpp.

Constructor & Destructor Documentation

◆ Options()

Options::Options ( int  argc,
char **  argv 
)

Ctor. Parses the command parameters given to the main function of the program.

Definition at line 45 of file LargeScaleOptions.cpp.

◆ ~Options()

Options::~Options ( )
virtual

Definition at line 431 of file LargeScaleOptions.cpp.

Member Function Documentation

◆ clusterPlanes()

bool Options::clusterPlanes ( ) const

True if region clustering without plane optimization is required.

Definition at line 341 of file LargeScaleOptions.cpp.

◆ colorRegions()

bool Options::colorRegions ( ) const

Returns true of region coloring is enabled.

Definition at line 343 of file LargeScaleOptions.cpp.

◆ doTextureAnalysis()

bool Options::doTextureAnalysis ( ) const

True if texture analysis is enabled.

Definition at line 319 of file LargeScaleOptions.cpp.

◆ extrude()

bool Options::extrude ( ) const

Whether to extend the grid. Enabled by default.

Definition at line 253 of file LargeScaleOptions.cpp.

◆ filenameSet()

bool Options::filenameSet ( ) const

Returns true if an output filen name was set.

Definition at line 321 of file LargeScaleOptions.cpp.

◆ generateTextures()

bool Options::generateTextures ( ) const

If true, textures will be generated during finalization of mesh.

Definition at line 347 of file LargeScaleOptions.cpp.

◆ getBGVoxelsize()

float Options::getBGVoxelsize ( ) const

Returns the given voxelsize for bigGrid.

Definition at line 235 of file LargeScaleOptions.cpp.

◆ getBigMesh()

bool Options::getBigMesh ( ) const

Returns if the new chunks should be written as a .ply-mesh.

Definition at line 212 of file LargeScaleOptions.cpp.

◆ getBufferSize()

unsigned int Options::getBufferSize ( ) const

Definition at line 279 of file LargeScaleOptions.cpp.

◆ getChunkSize()

int Options::getChunkSize ( ) const

Returns the chunksize.

Definition at line 239 of file LargeScaleOptions.cpp.

◆ getClassifier()

string Options::getClassifier ( ) const

Returns the name of the classifier used to color the mesh.

Definition at line 302 of file LargeScaleOptions.cpp.

◆ getCleanContourIterations()

int Options::getCleanContourIterations ( ) const

Number of iterations for contour cleanup.

Definition at line 257 of file LargeScaleOptions.cpp.

◆ getCoherenceThreshold()

unsigned int Options::getCoherenceThreshold ( ) const

Definition at line 366 of file LargeScaleOptions.cpp.

◆ getColorThreshold()

float Options::getColorThreshold ( ) const

Definition at line 368 of file LargeScaleOptions.cpp.

◆ getDanglingArtifacts()

int Options::getDanglingArtifacts ( ) const

Returns the number of dangling artifacts to remove from a created mesh.

Definition at line 255 of file LargeScaleOptions.cpp.

◆ getDebugChunks()

bool Options::getDebugChunks ( ) const

Returns if the mesh of every chunk additionally should be written as a .ply.

Definition at line 214 of file LargeScaleOptions.cpp.

◆ getDecomposition()

string Options::getDecomposition ( ) const

Returns the name of the used point cloud handler.

Definition at line 306 of file LargeScaleOptions.cpp.

◆ getDepth()

int Options::getDepth ( ) const

Returns the maximum recursion depth for region growing.

Definition at line 354 of file LargeScaleOptions.cpp.

◆ getEdgeCollapseMethod()

string Options::getEdgeCollapseMethod ( ) const

Edge collapse method.

Definition at line 304 of file LargeScaleOptions.cpp.

◆ getFeatureThreshold()

float Options::getFeatureThreshold ( ) const

Definition at line 372 of file LargeScaleOptions.cpp.

◆ getFillHoles()

int Options::getFillHoles ( ) const

Returns the region threshold for hole filling.

Definition at line 259 of file LargeScaleOptions.cpp.

◆ getFlippoint()

vector< float > Options::getFlippoint ( ) const

Returns the flipPoint for GPU normal computation.

Definition at line 408 of file LargeScaleOptions.cpp.

◆ getInputFileName()

vector< string > Options::getInputFileName ( ) const

Returns the output file name.

Definition at line 295 of file LargeScaleOptions.cpp.

◆ getIntersections()

int Options::getIntersections ( ) const

Returns the number of intersections. If the return value is positive it will be used for reconstruction instead of absolute voxelsize.

Definition at line 292 of file LargeScaleOptions.cpp.

◆ getKd()

int Options::getKd ( ) const

Returns the number of neighbors used for distance function evaluation.

Definition at line 247 of file LargeScaleOptions.cpp.

◆ getKi()

int Options::getKi ( ) const

Returns the number of neighbors for normal interpolation.

Definition at line 245 of file LargeScaleOptions.cpp.

◆ getKn()

int Options::getKn ( ) const

Returns the number of neighbors used for initial normal estimation.

Definition at line 249 of file LargeScaleOptions.cpp.

◆ getLineFusionThreshold()

float Options::getLineFusionThreshold ( ) const

Returns the fusion threshold for tesselation.

Definition at line 358 of file LargeScaleOptions.cpp.

◆ getLineReaderBuffer()

size_t Options::getLineReaderBuffer ( ) const

Definition at line 277 of file LargeScaleOptions.cpp.

◆ getMinimumTransformationVotes()

int Options::getMinimumTransformationVotes ( ) const

Definition at line 378 of file LargeScaleOptions.cpp.

◆ getMinPlaneSize()

int Options::getMinPlaneSize ( ) const

Minimum value for plane optimzation.

Definition at line 270 of file LargeScaleOptions.cpp.

◆ getNodeSize()

unsigned int Options::getNodeSize ( ) const

Only used in kd-tree (partMethod=0). Returns the maximum number of points in a leaf.

Definition at line 241 of file LargeScaleOptions.cpp.

◆ getNormalThreshold()

float Options::getNormalThreshold ( ) const

Returns the normal threshold for plane optimization.

Definition at line 266 of file LargeScaleOptions.cpp.

◆ getNumCCVColors()

unsigned int Options::getNumCCVColors ( ) const

Definition at line 364 of file LargeScaleOptions.cpp.

◆ getNumEdgeCollapses()

int Options::getNumEdgeCollapses ( ) const

Number of edge collapses.

Definition at line 310 of file LargeScaleOptions.cpp.

◆ getNumStatsColors()

unsigned int Options::getNumStatsColors ( ) const

Definition at line 362 of file LargeScaleOptions.cpp.

◆ getNumThreads()

int Options::getNumThreads ( ) const

Returns the number of used threads.

Definition at line 288 of file LargeScaleOptions.cpp.

◆ getOutputFolderPath()

string Options::getOutputFolderPath ( ) const

Definition at line 326 of file LargeScaleOptions.cpp.

◆ getPartMethod()

int Options::getPartMethod ( ) const

Retuns flag for partition-method (0 = kd-Tree; 1 = VGrid)

Definition at line 243 of file LargeScaleOptions.cpp.

◆ getPatternThreshold()

float Options::getPatternThreshold ( ) const

Definition at line 376 of file LargeScaleOptions.cpp.

◆ getPCM()

string Options::getPCM ( ) const

Returns the name of the used point cloud handler.

Definition at line 300 of file LargeScaleOptions.cpp.

◆ getPlaneIterations()

int Options::getPlaneIterations ( ) const

Returns to number plane optimization iterations.

Definition at line 268 of file LargeScaleOptions.cpp.

◆ getScaling()

float Options::getScaling ( ) const

Returns the scaling factor.

Definition at line 237 of file LargeScaleOptions.cpp.

◆ getScanPoseFile()

string Options::getScanPoseFile ( ) const

Returns the name of the given file with scan poses used for normal flipping.

Definition at line 308 of file LargeScaleOptions.cpp.

◆ getSharpCornerThreshold()

float Options::getSharpCornerThreshold ( ) const

Returns the sharp corner threshold when using sharp feature decomposition.

Definition at line 286 of file LargeScaleOptions.cpp.

◆ getSharpFeatureThreshold()

float Options::getSharpFeatureThreshold ( ) const

Returns the sharp feature threshold when using sharp feature decomposition.

Definition at line 284 of file LargeScaleOptions.cpp.

◆ getSmallRegionThreshold()

int Options::getSmallRegionThreshold ( ) const

Returns the threshold for the size of small region deletion after plane optimization.

Definition at line 349 of file LargeScaleOptions.cpp.

◆ getStatsCoeffs()

float * Options::getStatsCoeffs ( ) const

Definition at line 386 of file LargeScaleOptions.cpp.

◆ getStatsThreshold()

float Options::getStatsThreshold ( ) const

Definition at line 370 of file LargeScaleOptions.cpp.

◆ getTexelSize()

float Options::getTexelSize ( ) const

Returns the texel size for texture resolution.

Definition at line 356 of file LargeScaleOptions.cpp.

◆ getTexturePack()

string Options::getTexturePack ( ) const

Definition at line 360 of file LargeScaleOptions.cpp.

◆ getUseCrossCorr()

bool Options::getUseCrossCorr ( ) const

Definition at line 374 of file LargeScaleOptions.cpp.

◆ getUseNormals()

bool Options::getUseNormals ( ) const

Definition at line 382 of file LargeScaleOptions.cpp.

◆ getVolumenSize()

size_t Options::getVolumenSize ( ) const

Definition at line 383 of file LargeScaleOptions.cpp.

◆ getVoxelsize()

float Options::getVoxelsize ( ) const

Returns the first given voxelsize.

Definition at line 233 of file LargeScaleOptions.cpp.

◆ getVoxelSizes()

vector< float > Options::getVoxelSizes ( ) const

Returns all voxelsizes as a vector.

Definition at line 218 of file LargeScaleOptions.cpp.

◆ interpolateBoxes()

bool Options::interpolateBoxes ( ) const

Definition at line 380 of file LargeScaleOptions.cpp.

◆ onlyNormals()

bool Options::onlyNormals ( ) const

Definition at line 385 of file LargeScaleOptions.cpp.

◆ optimizePlanes()

bool Options::optimizePlanes ( ) const

Returns true if cluster optimization is enabled.

Definition at line 261 of file LargeScaleOptions.cpp.

◆ printUsage()

bool Options::printUsage ( ) const

Prints a usage message to stdout.

Definition at line 194 of file LargeScaleOptions.cpp.

◆ recalcNormals()

bool Options::recalcNormals ( ) const

If true, normals should be calculated even if they are already given in the input file.

Definition at line 331 of file LargeScaleOptions.cpp.

◆ retesselate()

bool Options::retesselate ( ) const

Return whether the mesh should be retesselated or not.

Definition at line 345 of file LargeScaleOptions.cpp.

◆ saveFaceNormals()

bool Options::saveFaceNormals ( ) const

Returns true if the face normals of the reconstructed mesh should be saved to an extra file ("face_normals.nor")

Definition at line 312 of file LargeScaleOptions.cpp.

◆ saveGrid()

bool Options::saveGrid ( ) const

Returns true if the Marching Cubes grid should be save.

Definition at line 337 of file LargeScaleOptions.cpp.

◆ saveNormals()

bool Options::saveNormals ( ) const

Returns true if the interpolated normals should be saved in the putput file.

Definition at line 335 of file LargeScaleOptions.cpp.

◆ saveOriginalData()

bool Options::saveOriginalData ( ) const

Returns true if the original points should be stored together with the reconstruction.

Definition at line 339 of file LargeScaleOptions.cpp.

◆ savePointNormals()

bool Options::savePointNormals ( ) const

Indicates whether to save the used points together with the interpolated normals.

Definition at line 333 of file LargeScaleOptions.cpp.

◆ useGPU()

bool Options::useGPU ( ) const

Returns if the GPU shuold be used for the normal estimation.

Definition at line 216 of file LargeScaleOptions.cpp.

◆ useRansac()

bool Options::useRansac ( ) const

If true, RANSAC based normal estimation is used.

Definition at line 251 of file LargeScaleOptions.cpp.

◆ writeClassificationResult()

bool Options::writeClassificationResult ( ) const

True if region clustering without plane optimization is required.

Definition at line 314 of file LargeScaleOptions.cpp.

Member Data Documentation

◆ m_bigMesh

bool LargeScaleOptions::Options::m_bigMesh
private

flag to generate a .ply file for the reconstructed mesh

Definition at line 389 of file LargeScaleOptions.hpp.

◆ m_bufferSize

unsigned int LargeScaleOptions::Options::m_bufferSize
private

Definition at line 535 of file LargeScaleOptions.hpp.

◆ m_chunkSize

int LargeScaleOptions::Options::m_chunkSize
private

gridsize for virtual grid

Definition at line 406 of file LargeScaleOptions.hpp.

◆ m_classifier

string LargeScaleOptions::Options::m_classifier
private

Name of the classifier object to color the mesh.

Definition at line 492 of file LargeScaleOptions.hpp.

◆ m_cleanContourIterations

int LargeScaleOptions::Options::m_cleanContourIterations
private

number of cleanContour iterations

Definition at line 430 of file LargeScaleOptions.hpp.

◆ m_coherenceThreshold

unsigned int LargeScaleOptions::Options::m_coherenceThreshold
private

Coherence threshold for texture matching based on color information.

Definition at line 515 of file LargeScaleOptions.hpp.

◆ m_colorThreshold

float LargeScaleOptions::Options::m_colorThreshold
private

Threshold for texture matching based on colors.

Definition at line 518 of file LargeScaleOptions.hpp.

◆ m_debugChunks

bool LargeScaleOptions::Options::m_debugChunks
private

flag to generate debug meshes for every chunk as a .ply

Definition at line 392 of file LargeScaleOptions.hpp.

◆ m_depth

int LargeScaleOptions::Options::m_depth
private

Maximum recursion depth for region growing.

Definition at line 480 of file LargeScaleOptions.hpp.

◆ m_ecm

string LargeScaleOptions::Options::m_ecm
private

Edge collapse method.

Definition at line 495 of file LargeScaleOptions.hpp.

◆ m_extrude

bool LargeScaleOptions::Options::m_extrude
private

extruded flag

Definition at line 424 of file LargeScaleOptions.hpp.

◆ m_faceNormalFile

string LargeScaleOptions::Options::m_faceNormalFile
private

The putput file name for face normals.

Definition at line 462 of file LargeScaleOptions.hpp.

◆ m_featuresThreshold

float LargeScaleOptions::Options::m_featuresThreshold
private

Threshold for texture matching based on features.

Definition at line 524 of file LargeScaleOptions.hpp.

◆ m_fillHoles

int LargeScaleOptions::Options::m_fillHoles
private

Threshold for hole filling.

Definition at line 433 of file LargeScaleOptions.hpp.

◆ m_flippoint

vector<float> LargeScaleOptions::Options::m_flippoint
private

flipPoint for GPU normal computation

Definition at line 421 of file LargeScaleOptions.hpp.

◆ m_generateTextures

bool LargeScaleOptions::Options::m_generateTextures
private

Whether or not the mesh should be retesselated while being finalized.

Definition at line 471 of file LargeScaleOptions.hpp.

◆ m_interpolateBoxes

bool LargeScaleOptions::Options::m_interpolateBoxes
private

Definition at line 539 of file LargeScaleOptions.hpp.

◆ m_intersections

int LargeScaleOptions::Options::m_intersections
private

The number of intersections used for reconstruction.

Definition at line 468 of file LargeScaleOptions.hpp.

◆ m_kd

int LargeScaleOptions::Options::m_kd
private

The number of neighbors for distance function evaluation.

Definition at line 415 of file LargeScaleOptions.hpp.

◆ m_ki

int LargeScaleOptions::Options::m_ki
private

The number of neighbors for normal interpolation.

Definition at line 412 of file LargeScaleOptions.hpp.

◆ m_kn

int LargeScaleOptions::Options::m_kn
private

The number of neighbors for normal estimation.

Definition at line 418 of file LargeScaleOptions.hpp.

◆ m_lineFusionThreshold

float LargeScaleOptions::Options::m_lineFusionThreshold
private

Threshold for line fusing when tesselating.

Definition at line 451 of file LargeScaleOptions.hpp.

◆ m_lineReaderBuffer

size_t LargeScaleOptions::Options::m_lineReaderBuffer
private

Definition at line 545 of file LargeScaleOptions.hpp.

◆ m_minimumTransformationVotes

int LargeScaleOptions::Options::m_minimumTransformationVotes
private

Minimum number of vote to consider a texture transformation as "correct".

Definition at line 533 of file LargeScaleOptions.hpp.

◆ m_minPlaneSize

int LargeScaleOptions::Options::m_minPlaneSize
private

Threshold for plane optimization.

Definition at line 442 of file LargeScaleOptions.hpp.

◆ m_numberOfDefaults

int LargeScaleOptions::Options::m_numberOfDefaults
private

The number of used default values.

Definition at line 465 of file LargeScaleOptions.hpp.

◆ m_numCCVColors

unsigned int LargeScaleOptions::Options::m_numCCVColors
private

Number of colors for texture matching based on color information.

Definition at line 512 of file LargeScaleOptions.hpp.

◆ m_numEdgeCollapses

int LargeScaleOptions::Options::m_numEdgeCollapses
private

Number of edge collapses.

Definition at line 498 of file LargeScaleOptions.hpp.

◆ m_numStatsColors

unsigned int LargeScaleOptions::Options::m_numStatsColors
private

Number of colors for texture statistics.

Definition at line 509 of file LargeScaleOptions.hpp.

◆ m_numThreads

int LargeScaleOptions::Options::m_numThreads
private

The number of used threads.

Definition at line 459 of file LargeScaleOptions.hpp.

◆ m_octreeNodeSize

unsigned int LargeScaleOptions::Options::m_octreeNodeSize
private

Definition at line 537 of file LargeScaleOptions.hpp.

◆ m_onlyNormals

bool LargeScaleOptions::Options::m_onlyNormals
private

Definition at line 547 of file LargeScaleOptions.hpp.

◆ m_outputFolderPath

string LargeScaleOptions::Options::m_outputFolderPath
private

Definition at line 500 of file LargeScaleOptions.hpp.

◆ m_partMethod

int LargeScaleOptions::Options::m_partMethod
private

sets partition method to kd-tree or virtual grid

Definition at line 409 of file LargeScaleOptions.hpp.

◆ m_patternThreshold

float LargeScaleOptions::Options::m_patternThreshold
private

Threshold for pattern extraction from textures.

Definition at line 530 of file LargeScaleOptions.hpp.

◆ m_pcm

string LargeScaleOptions::Options::m_pcm
private

The used point cloud manager.

Definition at line 477 of file LargeScaleOptions.hpp.

◆ m_planeIterations

int LargeScaleOptions::Options::m_planeIterations
private

Number of iterations for plane optimzation.

Definition at line 439 of file LargeScaleOptions.hpp.

◆ m_planeNormalThreshold

float LargeScaleOptions::Options::m_planeNormalThreshold
private

Threshold for plane optimization.

Definition at line 436 of file LargeScaleOptions.hpp.

◆ m_removeDanglingArtifacts

int LargeScaleOptions::Options::m_removeDanglingArtifacts
private

Number of dangling artifacts to remove.

Definition at line 427 of file LargeScaleOptions.hpp.

◆ m_retesselate

bool LargeScaleOptions::Options::m_retesselate
private

Whether or not the mesh should be retesselated while being finalized.

Definition at line 448 of file LargeScaleOptions.hpp.

◆ m_scaling

float LargeScaleOptions::Options::m_scaling
private

Definition at line 403 of file LargeScaleOptions.hpp.

◆ m_sct

float LargeScaleOptions::Options::m_sct
private

Sharp corner threshold when using sharp feature decomposition.

Definition at line 489 of file LargeScaleOptions.hpp.

◆ m_sft

float LargeScaleOptions::Options::m_sft
private

Sharp feature threshold when using sharp feature decomposition.

Definition at line 486 of file LargeScaleOptions.hpp.

◆ m_smallRegionThreshold

int LargeScaleOptions::Options::m_smallRegionThreshold
private

Threshold for small regions.

Definition at line 445 of file LargeScaleOptions.hpp.

◆ m_statsCoeffs

string LargeScaleOptions::Options::m_statsCoeffs
private

Coefficents file for texture matching based on statistics.

Definition at line 506 of file LargeScaleOptions.hpp.

◆ m_statsThreshold

float LargeScaleOptions::Options::m_statsThreshold
private

Threshold for texture matching based on statistics.

Definition at line 521 of file LargeScaleOptions.hpp.

◆ m_texelSize

float LargeScaleOptions::Options::m_texelSize
private

Texel size.

Definition at line 483 of file LargeScaleOptions.hpp.

◆ m_texturePack

string LargeScaleOptions::Options::m_texturePack
private

Path to texture pack.

Definition at line 503 of file LargeScaleOptions.hpp.

◆ m_use_normals

bool LargeScaleOptions::Options::m_use_normals
private

Definition at line 541 of file LargeScaleOptions.hpp.

◆ m_useCrossCorr

bool LargeScaleOptions::Options::m_useCrossCorr
private

Whether to use texture matching based on cross correlation.

Definition at line 527 of file LargeScaleOptions.hpp.

◆ m_volumenSize

size_t LargeScaleOptions::Options::m_volumenSize
private

Definition at line 543 of file LargeScaleOptions.hpp.

◆ m_voxelsize

float LargeScaleOptions::Options::m_voxelsize
private

The set voxelsize.

Definition at line 398 of file LargeScaleOptions.hpp.

◆ m_voxelsizeBG

float LargeScaleOptions::Options::m_voxelsizeBG
private

The set voxelsize for BigGrid.

Definition at line 401 of file LargeScaleOptions.hpp.

◆ m_voxelSizes

vector<float> LargeScaleOptions::Options::m_voxelSizes
private

The set voxelsizes.

Definition at line 395 of file LargeScaleOptions.hpp.

◆ m_writeClassificationResult

bool LargeScaleOptions::Options::m_writeClassificationResult
private

Whether or not the classifier shall dump meta data to a file 'clusters.clu'.

Definition at line 474 of file LargeScaleOptions.hpp.


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


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:26