src/tools/lvr2_largescale_reconstruct/Main.cpp
Go to the documentation of this file.
1 
28 #include "LargeScaleOptions.hpp"
31 #include <algorithm>
32 #include <iostream>
35 #include <random>
36 #include <string>
37 #include <lvr2/io/hdf5/ScanIO.hpp>
38 #include <boost/filesystem.hpp>
41 #include "lvr2/io/ScanIOUtils.hpp"
42 
43 using std::cout;
44 using std::endl;
45 using namespace lvr2;
46 
47 #if defined CUDA_FOUND
48 #define GPU_FOUND
49 
51 
52 typedef CudaSurface GpuSurface;
53 #elif defined OPENCL_FOUND
54 #define GPU_FOUND
55 
57 
58 
59 typedef ClSurface GpuSurface;
60 #endif
61 
63 // using ScanHDF5IO = lvr2::Hdf5Build<lvr2::hdf5features::ScanIO>;
64 
66 
67 // Extend IO with features (dependencies are automatically fetched)
69 
70 int main(int argc, char** argv)
71 {
72  // =======================================================================
73  // Parse and print command line parameters
74  // =======================================================================
75  // Parse command line arguments
77 
78  options.printLogo();
79 
80  // Exit if options had to generate a usage message
81  // (this means required parameters are missing)
82  if (options.printUsage())
83  {
84  return EXIT_SUCCESS;
85  }
86 
87  std::cout << options << std::endl;
88 
89  string in = options.getInputFileName()[0];
90 
91  boost::filesystem::path selectedFile(in);
92  string extension = selectedFile.extension().string();
93 
95 
96  LargeScaleReconstruction<Vec> lsr(options.getVoxelSizes(), options.getBGVoxelsize(), options.getScaling(),
97  options.getNodeSize(), options.getPartMethod(), options.getKi(), options.getKd(), options.getKn(),
98  options.useRansac(), options.getFlippoint(), options.extrude(), options.getDanglingArtifacts(),
99  options.getCleanContourIterations(), options.getFillHoles(), options.optimizePlanes(),
100  options.getNormalThreshold(), options.getPlaneIterations(), options.getMinPlaneSize(), options.getSmallRegionThreshold(),
101  options.retesselate(), options.getLineFusionThreshold(), options.getBigMesh(), options.getDebugChunks(), options.useGPU());
102 
103 
104 
105 
107  std::shared_ptr<ChunkHashGrid> cm;
108  BoundingBox<Vec> boundingBox;
109 
110  HDF5IO hdf;
111 
112  //reconstruction from hdf5
113  if (extension == ".h5")
114  {
115  // loadAllPreviewsFromHDF5(in, *project->project.get());
116  HDF5IO hdf;
117  hdf.open(in);
118  ScanProjectPtr scanProjectPtr = hdf.loadScanProject();
119  project->project = scanProjectPtr;
120 
121  for (int i = 0; i < project->project->positions.size(); i++)
122  {
123  project->changed.push_back(true);
124  }
125  cm = std::shared_ptr<ChunkHashGrid>(new ChunkHashGrid(in, 50, boundingBox, options.getChunkSize()));
126  }
127  else
128  {
129 
130  ScanProject dirScanProject;
131  bool importStatus = loadScanProject(in, dirScanProject);
132  //reconstruction from ScanProject Folder
133  if(importStatus) {
134  project->project = make_shared<ScanProject>(dirScanProject);
135  std::vector<bool> init(dirScanProject.positions.size(), true);
136  project->changed = init;
137  }
138  //reconstruction from a .ply file
139  else if(!boost::filesystem::is_directory(selectedFile))
140  {
141  project->project = ScanProjectPtr(new ScanProject);
142  ModelPtr model = ModelFactory::readModel(in);
143  ScanPtr scan(new Scan);
144 
145  scan->points = model->m_pointCloud;
146  ScanPositionPtr scanPosPtr = ScanPositionPtr(new ScanPosition());
147  scanPosPtr->scans.push_back(scan);
148  project->project->positions.push_back(scanPosPtr);
149  project->changed.push_back(true);
150  }
151  //reconstruction from a folder of .ply files
152  else{
153  project->project = ScanProjectPtr(new ScanProject);
154  boost::filesystem::directory_iterator it{in};
155  while (it != boost::filesystem::directory_iterator{})
156  {
157  cout << it->path().string() << endl;
158  string ext = it->path().extension().string();
159  if(ext == ".ply")
160  {
161  ModelPtr model = ModelFactory::readModel(it->path().string());
162  ScanPtr scan(new Scan);
163 
164  scan->points = model->m_pointCloud;
165  ScanPositionPtr scanPosPtr = ScanPositionPtr(new ScanPosition());
166  scanPosPtr->scans.push_back(scan);
167  project->project->positions.push_back(scanPosPtr);
168  project->changed.push_back(true);
169  }
170  it++;
171  }
172 
173 
174  }
175 
176  cm = std::shared_ptr<ChunkHashGrid>(new ChunkHashGrid("chunked_mesh.h5", 50, boundingBox, options.getChunkSize()));
177  }
178 
179  BoundingBox<Vec> bb;
180  // reconstruction with diffrent methods
181  if(options.getPartMethod() == 1)
182  {
183  int x = lsr.mpiChunkAndReconstruct(project, bb, cm);
184  }
185  else
186  {
187  int x = lsr.mpiAndReconstruct(project);
188  }
189 
190  // reconstruction of .ply for diffrent voxelSizes
191  if(options.getDebugChunks())
192  {
193 
194  for (int i; i < options.getVoxelSizes().size(); i++) {
195  lsr.getPartialReconstruct(bb, cm, options.getVoxelSizes()[i]);
196  }
197  }
198 
199  cout << "Program end." << endl;
200 
201  return 0;
202 }
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.
Definition: lvropenmp.cpp:56
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.
Definition: ScanTypes.hpp:98
A dynamic bounding box class.
Definition: BoundingBox.hpp:49
std::vector< ScanPositionPtr > positions
Vector of scan positions for this project.
Definition: ScanTypes.hpp:336
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.
void printLogo() const
Definition: BaseOption.cpp:110
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
Definition: ScanTypes.hpp:357
int getFillHoles() const
Returns the region threshold for hole filling.
CudaSurface GpuSurface
std::shared_ptr< ScanProject > ScanProjectPtr
Definition: ScanTypes.hpp:344
int getSmallRegionThreshold() const
Returns the threshold for the size of small region deletion after plane optimization.
std::shared_ptr< Model > ModelPtr
Definition: Model.hpp:80
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)
Definition: HDF5IO.cpp:232
std::shared_ptr< ScanPosition > ScanPositionPtr
Definition: ScanTypes.hpp:311
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.
char ** argv


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 Mon Feb 28 2022 22:46:08