Go to the documentation of this file.
35 #include <boost/filesystem.hpp>
69 if (model && model->m_pointCloud )
71 num_points = model->m_pointCloud->numPoints();
72 points = model->m_pointCloud->getPointArray();
73 cout <<
timestamp <<
"Read " << num_points <<
" points from " <<
filename << endl;
77 cout <<
timestamp <<
"Warning: No point cloud data found in " <<
filename << endl;
83 cout <<
timestamp <<
"Constructing kd-tree..." << endl;
85 cout <<
timestamp <<
"Finished kd-tree construction." << endl;
92 std::string method =
"RANSAC";
96 std::string method =
"PCA";
101 cout <<
timestamp <<
"Start Normal Calculation..." << endl;
105 cout <<
timestamp <<
"Finished Normal Calculation. " << endl;
108 model->m_pointCloud->setNormalArray(normals, num_points);
109 buffer = model->m_pointCloud;
133 auto grid = std::make_shared<PointsetGrid<Vec, BilinearFastBox<Vec>>>(
136 surface->getBoundingBox(),
141 grid->calcDistanceValues();
143 auto reconstruction = make_unique<FastReconstruction<Vec, BilinearFastBox<Vec>>>(grid);
144 reconstruction->getMesh(
mesh);
152 cout <<
timestamp <<
"Saving mesh." << endl;
163 boost::filesystem::path inFile(opt.
inputFile());
165 if(boost::filesystem::is_directory(inFile))
167 vector<float> all_points;
168 vector<float> all_normals;
170 boost::filesystem::directory_iterator lastFile;
171 for(boost::filesystem::directory_iterator it(inFile); it != lastFile; it++ )
173 boost::filesystem::path
p = boost::filesystem::canonical(it->path());
174 string currentFile =
p.filename().string();
176 if(
string(
p.extension().string().c_str()) ==
".3d")
180 if(sscanf(currentFile.c_str(),
"scan%3d", &num))
182 cout <<
timestamp <<
"Processing " <<
p.string() << endl;
202 size_t num_points = all_points.size() / 3;
205 size_t num_normals = all_normals.size() / 3;
207 buffer->setPointArray(points, num_points);
208 buffer->setNormalArray(normals, num_points);
boost::shared_array< float > floatArr
static void saveModel(ModelPtr m, std::string file)
void transformPointCloudAndAppend(PointBufferPtr &buffer, boost::filesystem::path &transfromFile, std::vector< float > &pts, std::vector< float > &nrm)
Transforms the given point buffer according to the transformation stored in transformFile and appends...
void reconstructAndSave(PointBufferPtr &buffer, cuda_normals::Options &opt)
std::shared_ptr< PointBuffer > PointBufferPtr
void computeNormals(string filename, cuda_normals::Options &opt, PointBufferPtr &buffer)
void getNormals(LBPointArray< float > &output_normals)
Get the resulting normals of the normal calculation. After calling "start".
A class to handle point information with an arbitrarily large number of attribute channels....
void calculateNormals()
Starts calculation the normals on GPU.
void setKn(int kn)
Set the number of k nearest neighbors k-neighborhood.
std::shared_ptr< PointsetSurface< BaseVecT > > PointsetSurfacePtr
string outputFile() const
bool exportPointNormals() const
A point cloud manager class that uses the STANN nearest neighbor search library to handle the data....
A class to parse the program options for the reconstruction executable.
float getVoxelsize() const
An interface class to wrap all functionality that is needed to generate a surface approximation from ...
static Timestamp timestamp
A global time stamp object for program runtime measurement.
void setFlippoint(float v_x, float v_y, float v_z)
Set the viewpoint to orientate the normals.
void setKi(int ki)
Set the number of k nearest neighbors k-neighborhood for interpolation.
std::shared_ptr< Model > ModelPtr
std::shared_ptr< MeshBuffer > MeshBufferPtr
void writePointsAndNormals(std::vector< float > &p, std::vector< float > &n, std::string outfile)
Writes the points and normals (float triples) stored in p and n to the given output file....
void setMethod(std::string &method)
Set Method for normal calculation.
static ModelPtr readModel(std::string filename)
int main(int argc, char **argv)
MeshBufferPtr apply(const BaseMesh< BaseVecT > &mesh)
Half-edge data structure implementing the BaseMesh interface.
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:24