src/tools/lvr2_reconstruct/Main.cpp
Go to the documentation of this file.
1 
29 #include <iostream>
30 #include <memory>
31 #include <tuple>
32 #include <stdlib.h>
33 
34 #include <boost/optional.hpp>
35 
37 
40 #include "lvr2/geometry/Normal.hpp"
54 //#include "lvr2/algorithm/ImageTexturizer.hpp"
55 
66 #include "lvr2/io/PointBuffer.hpp"
67 #include "lvr2/io/MeshBuffer.hpp"
68 #include "lvr2/io/ModelFactory.hpp"
69 #include "lvr2/io/PlutoMapIO.hpp"
70 #include "lvr2/util/Factories.hpp"
73 
74 #include "lvr2/geometry/BVH.hpp"
75 
77 
78 #include "Options.hpp"
79 
80 #if defined LVR2_USE_CUDA
81  #define GPU_FOUND
82 
84 
86 #elif defined LVR2_USE_OPENCL
87  #define GPU_FOUND
88 
91 #endif
92 
93 using boost::optional;
94 using std::unique_ptr;
95 using std::make_unique;
96 
97 using namespace lvr2;
98 
101 
102 template <typename BaseVecT>
104 {
105  // Create a point loader object
107 
108  // Parse loaded data
109  if (!model)
110  {
111  cout << timestamp << "IO Error: Unable to parse " << options.getInputFileName() << endl;
112  return nullptr;
113  }
114 
115  PointBufferPtr buffer = model->m_pointCloud;
116 
117  // Create a point cloud manager
118  string pcm_name = options.getPCM();
119  PointsetSurfacePtr<Vec> surface;
120 
121  // Create point set surface object
122  if(pcm_name == "PCL")
123  {
124  cout << timestamp << "Using PCL as point cloud manager is not implemented yet!" << endl;
125  panic_unimplemented("PCL as point cloud manager");
126  }
127  else if(pcm_name == "STANN" || pcm_name == "FLANN" || pcm_name == "NABO" || pcm_name == "NANOFLANN")
128  {
129 
130  int plane_fit_method = 0;
131 
132  if(options.useRansac())
133  {
134  plane_fit_method = 1;
135  }
136 
137  // plane_fit_method
138  // - 0: PCA
139  // - 1: RANSAC
140  // - 2: Iterative
141 
142  surface = make_shared<AdaptiveKSearchSurface<BaseVecT>>(
143  buffer,
144  pcm_name,
145  options.getKn(),
146  options.getKi(),
147  options.getKd(),
148  plane_fit_method,
149  options.getScanPoseFile()
150  );
151  }
152  else
153  {
154  cout << timestamp << "Unable to create PointCloudManager." << endl;
155  cout << timestamp << "Unknown option '" << pcm_name << "'." << endl;
156  return nullptr;
157  }
158 
159  // Set search options for normal estimation and distance evaluation
160  surface->setKd(options.getKd());
161  surface->setKi(options.getKi());
162  surface->setKn(options.getKn());
163 
164  // Calculate normals if necessary
165  if(!buffer->hasNormals() || options.recalcNormals())
166  {
167  if(options.useGPU())
168  {
169  #ifdef GPU_FOUND
170  std::vector<float> flipPoint = options.getFlippoint();
171  size_t num_points = buffer->numPoints();
172  floatArr points = buffer->getPointArray();
173  floatArr normals = floatArr(new float[ num_points * 3 ]);
174  std::cout << timestamp << "Generating GPU kd-tree" << std::endl;
175  GpuSurface gpu_surface(points, num_points);
176 
177 
178  gpu_surface.setKn(options.getKn());
179  gpu_surface.setKi(options.getKi());
180  gpu_surface.setFlippoint(flipPoint[0], flipPoint[1], flipPoint[2]);
181 
182  std::cout << timestamp << "Estimating Normals GPU" << std::endl;
183  gpu_surface.calculateNormals();
184  gpu_surface.getNormals(normals);
185 
186  buffer->setNormalArray(normals, num_points);
187  gpu_surface.freeGPU();
188  #else
189  std::cout << timestamp << "ERROR: GPU Driver not installed" << std::endl;
190  surface->calculateSurfaceNormals();
191  #endif
192  }
193  else
194  {
195  surface->calculateSurfaceNormals();
196  }
197  }
198  else
199  {
200  cout << timestamp << "Using given normals." << endl;
201  }
202 
203  return surface;
204 }
205 
206 std::pair<shared_ptr<GridBase>, unique_ptr<FastReconstructionBase<Vec>>>
210  )
211 {
212  // Determine whether to use intersections or voxelsize
213  bool useVoxelsize = options.getIntersections() <= 0;
214  float resolution = useVoxelsize ? options.getVoxelsize() : options.getIntersections();
215 
216  // Create a point set grid for reconstruction
217  string decompositionType = options.getDecomposition();
218 
219  // Fail safe check
220  if(decompositionType != "MT" && decompositionType != "MC" && decompositionType != "DMC" && decompositionType != "PMC" && decompositionType != "SF" )
221  {
222  cout << "Unsupported decomposition type " << decompositionType << ". Defaulting to PMC." << endl;
223  decompositionType = "PMC";
224  }
225 
226  if(decompositionType == "MC")
227  {
228  auto grid = std::make_shared<PointsetGrid<Vec, FastBox<Vec>>>(
229  resolution,
230  surface,
231  surface->getBoundingBox(),
232  useVoxelsize,
233  options.extrude()
234  );
235  grid->calcDistanceValues();
236  auto reconstruction = make_unique<FastReconstruction<Vec, FastBox<Vec>>>(grid);
237  return make_pair(grid, std::move(reconstruction));
238  }
239  else if(decompositionType == "PMC")
240  {
242  auto grid = std::make_shared<PointsetGrid<Vec, BilinearFastBox<Vec>>>(
243  resolution,
244  surface,
245  surface->getBoundingBox(),
246  useVoxelsize,
247  options.extrude()
248  );
249  grid->calcDistanceValues();
250  auto reconstruction = make_unique<FastReconstruction<Vec, BilinearFastBox<Vec>>>(grid);
251  return make_pair(grid, std::move(reconstruction));
252  }
253  // else if(decompositionType == "DMC")
254  // {
255  // auto reconstruction = make_unique<DMCReconstruction<Vec, FastBox<Vec>>>(
256  // surface,
257  // surface->getBoundingBox(),
258  // options.extrude()
259  // );
260  // return make_pair(nullptr, std::move(reconstruction));
261  // }
262  else if(decompositionType == "MT")
263  {
264  auto grid = std::make_shared<PointsetGrid<Vec, TetraederBox<Vec>>>(
265  resolution,
266  surface,
267  surface->getBoundingBox(),
268  useVoxelsize,
269  options.extrude()
270  );
271  grid->calcDistanceValues();
272  auto reconstruction = make_unique<FastReconstruction<Vec, TetraederBox<Vec>>>(grid);
273  return make_pair(grid, std::move(reconstruction));
274  }
275  else if(decompositionType == "SF")
276  {
277  SharpBox<Vec>::m_surface = surface;
278  auto grid = std::make_shared<PointsetGrid<Vec, SharpBox<Vec>>>(
279  resolution,
280  surface,
281  surface->getBoundingBox(),
282  useVoxelsize,
283  options.extrude()
284  );
285  grid->calcDistanceValues();
286  auto reconstruction = make_unique<FastReconstruction<Vec, SharpBox<Vec>>>(grid);
287  return make_pair(grid, std::move(reconstruction));
288  }
289 
290  return make_pair(nullptr, nullptr);
291 }
292 
293 int main(int argc, char** argv)
294 {
295  // =======================================================================
296  // Parse and print command line parameters
297  // =======================================================================
298  // Parse command line arguments
299  reconstruct::Options options(argc, argv);
300 
301  options.printLogo();
302 
303  // Exit if options had to generate a usage message
304  // (this means required parameters are missing)
305  if (options.printUsage())
306  {
307  return EXIT_SUCCESS;
308  }
309 
310  std::cout << options << std::endl;
311 
312  // =======================================================================
313  // Load (and potentially store) point cloud
314  // =======================================================================
316 
317  auto surface = loadPointCloud<Vec>(options);
318  if (!surface)
319  {
320  cout << "Failed to create pointcloud. Exiting." << endl;
321  return EXIT_FAILURE;
322  }
323 
324  // Save points and normals only
325  if(options.savePointNormals())
326  {
327  ModelPtr pn(new Model(surface->pointBuffer()));
328  ModelFactory::saveModel(pn, "pointnormals.ply");
329  }
330 
331  // =======================================================================
332  // Reconstruct mesh from point cloud data
333  // =======================================================================
334  // Create an empty mesh
336 
337  shared_ptr<GridBase> grid;
338  unique_ptr<FastReconstructionBase<Vec>> reconstruction;
339  std::tie(grid, reconstruction) = createGridAndReconstruction(options, surface);
340 
341  // Reconstruct mesh
342  reconstruction->getMesh(mesh);
343 
344  // Save grid to file
345  if(options.saveGrid() && grid)
346  {
347  grid->saveGrid("fastgrid.grid");
348  }
349 
350  // =======================================================================
351  // Optimize mesh
352  // =======================================================================
353  if(options.getDanglingArtifacts())
354  {
355  cout << timestamp << "Removing dangling artifacts" << endl;
356  removeDanglingCluster(mesh, static_cast<size_t>(options.getDanglingArtifacts()));
357  }
358 
359  // Magic number from lvr1 `cleanContours`...
360  cleanContours(mesh, options.getCleanContourIterations(), 0.0001);
361 
362  // Fill small holes if requested
363  if(options.getFillHoles())
364  {
365  naiveFillSmallHoles(mesh, options.getFillHoles(), false);
366  }
367 
368  // Calculate initial face normals
369  auto faceNormals = calcFaceNormals(mesh);
370 
371  // Reduce mesh complexity
372  const auto reductionRatio = options.getEdgeCollapseReductionRatio();
373  if (reductionRatio > 0.0)
374  {
375  if (reductionRatio > 1.0)
376  {
377  throw "The reduction ratio needs to be between 0 and 1!";
378  }
379 
380  // Each edge collapse removes two faces in the general case.
381  // TODO: maybe we should calculate this differently...
382  const auto count = static_cast<size_t>((mesh.numFaces() / 2) * reductionRatio);
383  auto collapsedCount = simpleMeshReduction(mesh, count, faceNormals);
384  }
385 
386  ClusterBiMap<FaceHandle> clusterBiMap;
387  if(options.optimizePlanes())
388  {
390  mesh,
391  faceNormals,
392  options.getNormalThreshold(),
393  options.getPlaneIterations(),
394  options.getMinPlaneSize()
395  );
396 
397  if(options.getSmallRegionThreshold() > 0)
398  {
399  deleteSmallPlanarCluster(mesh, clusterBiMap, static_cast<size_t>(options.getSmallRegionThreshold()));
400  }
401 
402  if(options.getFillHoles())
403  {
404  naiveFillSmallHoles(mesh, options.getFillHoles(), false);
405  }
406 
407  cleanContours(mesh, options.getCleanContourIterations(), 0.0001);
408 
409  if (options.retesselate())
410  {
411  Tesselator<Vec>::apply(mesh, clusterBiMap, faceNormals, options.getLineFusionThreshold());
412  }
413  }
414  else
415  {
416  clusterBiMap = planarClusterGrowing(mesh, faceNormals, options.getNormalThreshold());
417  }
418 
419  // =======================================================================
420  // Finalize mesh
421  // =======================================================================
422  // Prepare color data for finalizing
423  ClusterPainter painter(clusterBiMap);
424  auto clusterColors = boost::optional<DenseClusterMap<Rgb8Color>>(painter.simpsons(mesh));
425  auto vertexColors = calcColorFromPointCloud(mesh, surface);
426 
427  // Calc normals for vertices
428  auto vertexNormals = calcVertexNormals(mesh, faceNormals, *surface);
429 
430  // Prepare finalize algorithm
431  TextureFinalizer<Vec> finalize(clusterBiMap);
432  finalize.setVertexNormals(vertexNormals);
433 
434  // TODO:
435  // Vielleicht sollten indv. vertex und cluster colors mit in den Materializer aufgenommen werden
436  // Dafür spricht: alles mit Farben findet dann an derselben Stelle statt
437  // dagegen spricht: Materializer macht aktuell nur face colors und keine vertex colors
438 
439  // Vertex colors:
440  // If vertex colors should be generated from pointcloud:
441  if (options.vertexColorsFromPointcloud())
442  {
443  // set vertex color data from pointcloud
444  finalize.setVertexColors(*vertexColors);
445  }
446  else if (clusterColors)
447  {
448  // else: use simpsons painter for vertex coloring
449  finalize.setClusterColors(*clusterColors);
450  }
451 
452  // Materializer for face materials (colors and/or textures)
453  Materializer<Vec> materializer(
454  mesh,
455  clusterBiMap,
456  faceNormals,
457  *surface
458  );
459 
460  // ImageTexturizer<Vec> img_texter(
461  // options.getTexelSize(),
462  // options.getTexMinClusterSize(),
463  // options.getTexMaxClusterSize()
464  // );
465 
466  Texturizer<Vec> texturizer(
467  options.getTexelSize(),
468  options.getTexMinClusterSize(),
469  options.getTexMaxClusterSize()
470  );
471 
472  // When using textures ...
473  if (options.generateTextures())
474  {
475  if (!options.texturesFromImages())
476  {
477  materializer.setTexturizer(texturizer);
478  }
479  else
480  {
481  // cout << "ScanProject" << endl;
482  // ScanprojectIO project;
483 
484  // if (options.getProjectDir().empty())
485  // {
486  // cout << "Empty" << endl;
487  // project.parse_project(options.getInputFileName());
488  // }
489  // else
490  // {
491  // cout << "Not empty" << endl;
492  // project.parse_project(options.getProjectDir());
493  // }
494 
495  // img_texter.set_project(project.get_project());
496 
497  // materializer.setTexturizer(img_texter);
498  }
499  }
500 
501  // Generate materials
502  MaterializerResult<Vec> matResult = materializer.generateMaterials();
503 
504  // Add material data to finalize algorithm
505  finalize.setMaterializerResult(matResult);
506  // Run finalize algorithm
507  auto buffer = finalize.apply(mesh);
508 
509  // When using textures ...
510  if (options.generateTextures())
511  {
512  // Set optioins to save them to disk
513  materializer.saveTextures();
514  buffer->addIntAtomic(1, "mesh_save_textures");
515  buffer->addIntAtomic(1, "mesh_texture_image_extension");
516  }
517 
518  // =======================================================================
519  // Write all results (including the mesh) to file
520  // =======================================================================
521  // Create output model and save to file
522  auto m = ModelPtr( new Model(buffer));
523 
524  if(options.saveOriginalData())
525  {
526  m->m_pointCloud = surface->pointBuffer();
527 
528  cout << "REPAIR SAVING" << endl;
529  }
530 
531  for(const std::string& output_filename : options.getOutputFileNames())
532  {
533  cout << timestamp << "Saving mesh to "<< output_filename << "." << endl;
534  ModelFactory::saveModel(m, output_filename);
535  }
536 
537  if (matResult.m_keypoints)
538  {
539  // save materializer keypoints to hdf5 which is not possible with ModelFactory
540  //PlutoMapIO map_io("triangle_mesh.h5");
541  //map_io.addTextureKeypointsMap(matResult.m_keypoints.get());
542  }
543 
544  cout << timestamp << "Program end." << endl;
545 
546  return 0;
547 }
void setVertexColors(const VertexMap< Rgb8Color > &vertexColors)
ClusterBiMap< FaceHandle > iterativePlanarClusterGrowingRANSAC(BaseMesh< BaseVecT > &mesh, FaceMap< Normal< typename BaseVecT::CoordType >> &normals, float minSinAngle, int numIterations, int minClusterSize, int ransacIterations=100, int ransacSamples=10)
Algorithm which generates planar clusters from the given mesh, drags points in clusters into regressi...
bool printUsage() const
Prints a usage message to stdout.
void calculateNormals()
Starts calculation the normals on GPU.
void setFlippoint(float v_x, float v_y, float v_z)
Set the viewpoint to orientate the normals.
void setClusterColors(const ClusterMap< Rgb8Color > &colors)
size_t simpleMeshReduction(BaseMesh< BaseVecT > &mesh, const size_t count, FaceMap< Normal< typename BaseVecT::CoordType >> &faceNormals)
Like iterativeEdgeCollapse but with a fixed cost function.
void deleteSmallPlanarCluster(BaseMesh< BaseVecT > &mesh, ClusterBiMap< FaceHandle > &clusters, size_t smallClusterThreshold)
Removes all clusters and their cotained faces from the given mesh which are smaller than the given sm...
HalfEdgeMesh< Vec > mesh
const kaboom::Options * options
Algorithm which generates the same color for all vertices, which are in the same cluster.
static void apply(BaseMesh< BaseVecT > &mesh, ClusterBiMap< FaceHandle > &clusters, DenseFaceMap< Normal< typename BaseVecT::CoordType >> &faceNormals, float lineFusionThreshold)
int getPlaneIterations() const
Returns to number plane optimization iterations.
DenseVertexMap< Normal< typename BaseVecT::CoordType > > calcVertexNormals(const BaseMesh< BaseVecT > &mesh, const FaceMap< Normal< typename BaseVecT::CoordType >> &normals, const PointsetSurface< BaseVecT > &surface)
Calculates a normal for each vertex in the mesh.
bool saveGrid() const
Returns true if the Marching Cubes grid should be save.
void removeDanglingCluster(BaseMesh< BaseVecT > &mesh, size_t sizeThreshold)
int getDanglingArtifacts() const
Returns the number of dangling artifacts to remove from a created mesh.
int main(int argc, char **argv)
bool recalcNormals() const
If true, normals should be calculated even if they are already given in the input file...
int getKd() const
Returns the number of neighbors used for distance function evaluation.
static Timestamp timestamp
A global time stamp object for program runtime measurement.
Definition: Timestamp.hpp:116
An interface class to wrap all functionality that is needed to generate a surface approximation from ...
static ModelPtr readModel(std::string filename)
size_t naiveFillSmallHoles(BaseMesh< BaseVecT > &mesh, size_t maxSize, bool collapseOnly)
Fills holes consisting of less than or equal to maxSize edges.
boost::optional< DenseVertexMap< Rgb8Color > > calcColorFromPointCloud(const BaseMesh< BaseVecT > &mesh, const PointsetSurfacePtr< BaseVecT > surface)
Calculates the color of each vertex from the point cloud.
static void setNumThreads(int n)
Sets the number of used threads if OpenMP is used for parallelization.
Definition: lvropenmp.cpp:56
DenseFaceMap< Normal< typename BaseVecT::CoordType > > calcFaceNormals(const BaseMesh< BaseVecT > &mesh)
Calculates a normal for each face in the mesh.
vector< string > getOutputFileNames() const
Returns the output file names.
bool retesselate() const
Return whether the mesh should be retesselated or not.
int getCleanContourIterations() const
Number of iterations for contour cleanup.
float getTexelSize() const
Returns the texel size for texture resolution.
int getKn() const
Returns the number of neighbors used for initial normal estimation.
int getKi() const
Returns the number of neighbors for normal interpolation.
Class for calculating materials for each cluster of a given mesh.
void setVertexNormals(const VertexMap< Normal< typename BaseVecT::CoordType >> &normals)
std::shared_ptr< PointBuffer > PointBufferPtr
bool extrude() const
Whether to extend the grid. Enable by default.
A map of clusters, which also saves a back-reference from handle to cluster.
void cleanContours(BaseMesh< BaseVecT > &mesh, int iterations, float areaThreshold)
Removes faces with a high number of boundary edges.
void printLogo() const
Definition: BaseOption.cpp:110
int getNumThreads() const
Returns the number of used threads.
int getSmallRegionThreshold() const
Returns the threshold for the size of small region deletion after plane optimization.
float getVoxelsize() const
Returns the given voxelsize.
string getDecomposition() const
Returns the name of the used point cloud handler.
std::pair< shared_ptr< GridBase >, unique_ptr< FastReconstructionBase< Vec > > > createGridAndReconstruction(const reconstruct::Options &options, PointsetSurfacePtr< Vec > surface)
PointsetSurfacePtr< BaseVecT > loadPointCloud(const reconstruct::Options &options)
Used for extended marching cubes Reconstruction.
Definition: SharpBox.hpp:53
void setKn(int kn)
Set the number of k nearest neighbors k-neighborhood.
void setMaterializerResult(const MaterializerResult< BaseVecT > &materializerResult)
int getMinPlaneSize() const
Minimum value for plane optimzation.
void getNormals(LBPointArray< float > &output_normals)
Get the resulting normals of the normal calculation. After calling "start".
MaterializerResult< BaseVecT > generateMaterials()
Generates materials.
void setKi(int ki)
Set the number of k nearest neighbors k-neighborhood for interpolation.
boost::shared_array< float > floatArr
Definition: DataStruct.hpp:133
float getNormalThreshold() const
Returns the normal threshold for plane optimization.
Half-edge data structure implementing the BaseMesh interface.
bool saveOriginalData() const
Returns true if the original points should be stored together with the reconstruction.
size_t numFaces() const final
Returns the number of faces in the mesh.
CudaSurface GpuSurface
int getFillHoles() const
Returns the region threshold for hole filling.
Class that performs texture-related tasks.
Definition: Texturizer.hpp:63
boost::optional< std::unordered_map< BaseVecT, std::vector< float > > > m_keypoints
Keypoints.
string getScanPoseFile() const
Returns the name of the given file with scan poses used for normal flipping.
string getInputFileName() const
Returns the input file name.
float getEdgeCollapseReductionRatio() const
Reduction ratio for mesh reduction via edge collapse.
int getIntersections() const
Returns the number of intersections. If the return value is positive it will be used for reconstructi...
std::shared_ptr< Model > ModelPtr
Definition: Model.hpp:80
void panic_unimplemented(std::string msg)
Throws a panic exception with the given error message and denotes that the exception was thrown due t...
Definition: Panic.hpp:84
bool generateTextures() const
If true, textures will be generated during finalization of mesh.
ClusterBiMap< FaceHandle > planarClusterGrowing(const BaseMesh< BaseVecT > &mesh, const FaceMap< Normal< typename BaseVecT::CoordType >> &normals, float minSinAngle)
Algorithm which generates plane clusters from the given mesh.
MeshBufferPtr apply(const BaseMesh< BaseVecT > &mesh)
A class to parse the program options for the reconstruction executable.
Result struct for the materializer.
bool savePointNormals() const
Indicates whether to save the used points together with the interpolated normals. ...
bool useRansac() const
If true, RANSAC based normal estimation is used.
std::shared_ptr< PointsetSurface< BaseVecT > > PointsetSurfacePtr
bool optimizePlanes() const
Returns true if cluster optimization is enabled.
float getLineFusionThreshold() const
Returns the fusion threshold for tesselation.
void setTexturizer(Texturizer< BaseVecT > &texturizer)
Sets the texturizer.
void saveTextures()
Saves the textures by calling the saveTextures() method of the texturizer.
string getPCM() const
Returns the name of the used point cloud handler.
static void saveModel(ModelPtr m, std::string file)
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