34 #include <boost/optional.hpp> 80 #if defined LVR2_USE_CUDA 86 #elif defined LVR2_USE_OPENCL 93 using boost::optional;
94 using std::unique_ptr;
95 using std::make_unique;
102 template <
typename BaseVecT>
118 string pcm_name = options.
getPCM();
122 if(pcm_name ==
"PCL")
124 cout <<
timestamp <<
"Using PCL as point cloud manager is not implemented yet!" << endl;
127 else if(pcm_name ==
"STANN" || pcm_name ==
"FLANN" || pcm_name ==
"NABO" || pcm_name ==
"NANOFLANN")
130 int plane_fit_method = 0;
134 plane_fit_method = 1;
142 surface = make_shared<AdaptiveKSearchSurface<BaseVecT>>(
154 cout <<
timestamp <<
"Unable to create PointCloudManager." << endl;
155 cout <<
timestamp <<
"Unknown option '" << pcm_name <<
"'." << endl;
160 surface->setKd(options.
getKd());
161 surface->setKi(options.
getKi());
162 surface->setKn(options.
getKn());
171 size_t num_points = buffer->numPoints();
172 floatArr points = buffer->getPointArray();
174 std::cout <<
timestamp <<
"Generating GPU kd-tree" << std::endl;
180 gpu_surface.
setFlippoint(flipPoint[0], flipPoint[1], flipPoint[2]);
182 std::cout <<
timestamp <<
"Estimating Normals GPU" << std::endl;
186 buffer->setNormalArray(normals, num_points);
189 std::cout <<
timestamp <<
"ERROR: GPU Driver not installed" << std::endl;
190 surface->calculateSurfaceNormals();
195 surface->calculateSurfaceNormals();
200 cout <<
timestamp <<
"Using given normals." << endl;
206 std::pair<shared_ptr<GridBase>, unique_ptr<FastReconstructionBase<Vec>>>
220 if(decompositionType !=
"MT" && decompositionType !=
"MC" && decompositionType !=
"DMC" && decompositionType !=
"PMC" && decompositionType !=
"SF" )
222 cout <<
"Unsupported decomposition type " << decompositionType <<
". Defaulting to PMC." << endl;
223 decompositionType =
"PMC";
226 if(decompositionType ==
"MC")
228 auto grid = std::make_shared<PointsetGrid<Vec, FastBox<Vec>>>(
231 surface->getBoundingBox(),
235 grid->calcDistanceValues();
236 auto reconstruction = make_unique<FastReconstruction<Vec, FastBox<Vec>>>(grid);
237 return make_pair(grid, std::move(reconstruction));
239 else if(decompositionType ==
"PMC")
242 auto grid = std::make_shared<PointsetGrid<Vec, BilinearFastBox<Vec>>>(
245 surface->getBoundingBox(),
249 grid->calcDistanceValues();
250 auto reconstruction = make_unique<FastReconstruction<Vec, BilinearFastBox<Vec>>>(grid);
251 return make_pair(grid, std::move(reconstruction));
262 else if(decompositionType ==
"MT")
264 auto grid = std::make_shared<PointsetGrid<Vec, TetraederBox<Vec>>>(
267 surface->getBoundingBox(),
271 grid->calcDistanceValues();
272 auto reconstruction = make_unique<FastReconstruction<Vec, TetraederBox<Vec>>>(grid);
273 return make_pair(grid, std::move(reconstruction));
275 else if(decompositionType ==
"SF")
278 auto grid = std::make_shared<PointsetGrid<Vec, SharpBox<Vec>>>(
281 surface->getBoundingBox(),
285 grid->calcDistanceValues();
286 auto reconstruction = make_unique<FastReconstruction<Vec, SharpBox<Vec>>>(grid);
287 return make_pair(grid, std::move(reconstruction));
290 return make_pair(
nullptr,
nullptr);
310 std::cout << options << std::endl;
317 auto surface = loadPointCloud<Vec>(
options);
320 cout <<
"Failed to create pointcloud. Exiting." << endl;
337 shared_ptr<GridBase> grid;
338 unique_ptr<FastReconstructionBase<Vec>> reconstruction;
342 reconstruction->getMesh(mesh);
347 grid->saveGrid(
"fastgrid.grid");
355 cout <<
timestamp <<
"Removing dangling artifacts" << endl;
373 if (reductionRatio > 0.0)
375 if (reductionRatio > 1.0)
377 throw "The reduction ratio needs to be between 0 and 1!";
382 const auto count =
static_cast<size_t>((mesh.
numFaces() / 2) * reductionRatio);
424 auto clusterColors = boost::optional<DenseClusterMap<Rgb8Color>>(painter.simpsons(mesh));
446 else if (clusterColors)
507 auto buffer = finalize.
apply(mesh);
514 buffer->addIntAtomic(1,
"mesh_save_textures");
515 buffer->addIntAtomic(1,
"mesh_texture_image_extension");
526 m->m_pointCloud = surface->pointBuffer();
528 cout <<
"REPAIR SAVING" << endl;
533 cout <<
timestamp <<
"Saving mesh to "<< output_filename <<
"." << endl;
544 cout <<
timestamp <<
"Program end." << endl;
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.
int getTexMaxClusterSize() const
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...
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.
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.
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)
vector< float > getFlippoint() const
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.
bool vertexColorsFromPointcloud() const
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.
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
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.
int getFillHoles() const
Returns the region threshold for hole filling.
Class that performs texture-related tasks.
boost::optional< std::unordered_map< BaseVecT, std::vector< float > > > m_keypoints
Keypoints.
int getTexMinClusterSize() const
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
void panic_unimplemented(std::string msg)
Throws a panic exception with the given error message and denotes that the exception was thrown due t...
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 texturesFromImages() const
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)