38 #include <boost/filesystem.hpp> 47 #if defined CUDA_FOUND 53 #elif defined OPENCL_FOUND 87 std::cout << options << std::endl;
91 boost::filesystem::path selectedFile(in);
92 string extension = selectedFile.extension().string();
107 std::shared_ptr<ChunkHashGrid> cm;
113 if (extension ==
".h5")
119 project->project = scanProjectPtr;
121 for (
int i = 0; i < project->project->positions.size(); i++)
123 project->changed.push_back(
true);
134 project->project = make_shared<ScanProject>(dirScanProject);
135 std::vector<bool> init(dirScanProject.
positions.size(),
true);
136 project->changed = init;
139 else if(!boost::filesystem::is_directory(selectedFile))
145 scan->points = model->m_pointCloud;
147 scanPosPtr->scans.push_back(scan);
148 project->project->positions.push_back(scanPosPtr);
149 project->changed.push_back(
true);
154 boost::filesystem::directory_iterator it{in};
155 while (it != boost::filesystem::directory_iterator{})
157 cout << it->path().string() << endl;
158 string ext = it->path().extension().string();
164 scan->points = model->m_pointCloud;
166 scanPosPtr->scans.push_back(scan);
167 project->project->positions.push_back(scanPosPtr);
168 project->changed.push_back(
true);
183 int x = lsr.mpiChunkAndReconstruct(project, bb, cm);
187 int x = lsr.mpiAndReconstruct(project);
195 lsr.getPartialReconstruct(bb, cm, options.
getVoxelSizes()[i]);
199 cout <<
"Program end." << endl;
float getLineFusionThreshold() const
Returns the fusion threshold for tesselation.
bool optimizePlanes() const
Returns true if cluster optimization is enabled.
int getNumThreads() const
Returns the number of used threads.
int getDanglingArtifacts() const
Returns the number of dangling artifacts to remove from a created mesh.
const kaboom::Options * options
A class to parse the program options for the reconstruction executable.
bool extrude() const
Whether to extend the grid. Enabled by default.
int getPartMethod() const
Retuns flag for partition-method (0 = kd-Tree; 1 = VGrid)
ScanProjectPtr loadScanProject()
static ModelPtr readModel(std::string filename)
static void setNumThreads(int n)
Sets the number of used threads if OpenMP is used for parallelization.
typename add_features_with_deps< F... >::type AddFeatures
bool useGPU() const
Returns if the GPU shuold be used for the normal estimation.
int getKn() const
Returns the number of neighbors used for initial normal estimation.
bool printUsage() const
Prints a usage message to stdout.
std::shared_ptr< Scan > ScanPtr
Shared pointer to scans.
A dynamic bounding box class.
std::vector< ScanPositionPtr > positions
Vector of scan positions for this project.
int getKi() const
Returns the number of neighbors for normal interpolation.
bool getDebugChunks() const
Returns if the mesh of every chunk additionally should be written as a .ply.
float getNormalThreshold() const
Returns the normal threshold for plane optimization.
float getScaling() const
Returns the scaling factor.
int getPlaneIterations() const
Returns to number plane optimization iterations.
std::vector< string > getInputFileName() const
Returns the output file name.
int getMinPlaneSize() const
Minimum value for plane optimzation.
vector< float > getFlippoint() const
Returns the flipPoint for GPU normal computation.
Manager Class for all Hdf5IO components located in hdf5 directory.
std::shared_ptr< ScanProjectEditMark > ScanProjectEditMarkPtr
int getFillHoles() const
Returns the region threshold for hole filling.
std::shared_ptr< ScanProject > ScanProjectPtr
int getSmallRegionThreshold() const
Returns the threshold for the size of small region deletion after plane optimization.
std::shared_ptr< Model > ModelPtr
int getCleanContourIterations() const
Number of iterations for contour cleanup.
unsigned int getNodeSize() const
Only used in kd-tree (partMethod=0). Returns the maximum number of points in a leaf.
bool useRansac() const
If true, RANSAC based normal estimation is used.
bool loadScanProject(const boost::filesystem::path &root, ScanProject &scanProj)
bool retesselate() const
Return whether the mesh should be retesselated or not.
int getKd() const
Returns the number of neighbors used for distance function evaluation.
int main(int argc, char **argv)
int getChunkSize() const
Returns the chunksize.
bool open(std::string filename, int open_flag)
std::shared_ptr< ScanPosition > ScanPositionPtr
float getBGVoxelsize() const
Returns the given voxelsize for bigGrid.
vector< float > getVoxelSizes() const
Returns all voxelsizes as a vector.
bool getBigMesh() const
Returns if the new chunks should be written as a .ply-mesh.