35 #include <boost/filesystem.hpp> 61 if (model && model->m_pointCloud )
63 num_points = model->m_pointCloud->numPoints();
64 points = model->m_pointCloud->getPointArray();
65 cout <<
timestamp <<
"Read " << num_points <<
" points from " << filename << endl;
69 cout <<
timestamp <<
"Warning: No point cloud data found in " << filename << endl;
75 cout <<
timestamp <<
"Constructing kd-tree..." << endl;
76 ClSurface gpu_surface(points, num_points);
77 cout <<
timestamp <<
"Finished kd-tree construction." << endl;
91 cout <<
timestamp <<
"Start Normal Calculation..." << endl;
95 cout <<
timestamp <<
"Finished Normal Calculation. " << endl;
97 buffer->setPointArray(points, num_points);
98 buffer->setNormalArray(normals, num_points);
122 auto grid = std::make_shared<PointsetGrid<Vec, BilinearFastBox<Vec>>>(
125 surface->getBoundingBox(),
130 grid->calcDistanceValues();
132 auto reconstruction = make_unique<FastReconstruction<Vec, BilinearFastBox<Vec>>>(grid);
133 reconstruction->getMesh(mesh);
141 cout <<
timestamp <<
"Saving mesh." << endl;
152 boost::filesystem::path inFile(opt.
inputFile());
154 if(boost::filesystem::is_directory(inFile))
156 vector<float> all_points;
157 vector<float> all_normals;
159 boost::filesystem::directory_iterator lastFile;
160 for(boost::filesystem::directory_iterator it(inFile); it != lastFile; it++ )
162 boost::filesystem::path
p = boost::filesystem::canonical(it->path());
163 string currentFile = p.filename().string();
165 if(
string(p.extension().string().c_str()) ==
".3d")
169 if(sscanf(currentFile.c_str(),
"scan%3d", &num))
171 cout <<
timestamp <<
"Processing " << p.string() << endl;
191 size_t num_points = all_points.size() / 3;
194 size_t num_normals = all_normals.size() / 3;
196 buffer->setPointArray(points, num_points);
197 buffer->setNormalArray(normals, num_normals);
A class to handle point information with an arbitrarily large number of attribute channels...
void setKi(int ki)
Set the number of k nearest neighbors k-neighborhood for interpolation.
std::shared_ptr< MeshBuffer > MeshBufferPtr
static Timestamp timestamp
A global time stamp object for program runtime measurement.
void calculateNormals()
Starts calculation the normals on GPU.
void setMethod(std::string method)
Set Method for normal calculation.
static ModelPtr readModel(std::string filename)
MeshBufferPtr apply(const BaseMesh< BaseVecT > &mesh)
void setFlippoint(float v_x, float v_y, float v_z)
Set the viewpoint to orientate the normals.
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...
std::shared_ptr< PointBuffer > PointBufferPtr
void reconstructAndSave(PointBufferPtr &buffer, cl_normals::Options &opt)
string outputFile() const
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 setKn(int kn)
Set the number of k nearest neighbors k-neighborhood.
boost::shared_array< float > floatArr
Half-edge data structure implementing the BaseMesh interface.
A class to parse the program options for the reconstruction executable.
A point cloud manager class that uses the STANN nearest neighbor search library to handle the data...
void computeNormals(string filename, cl_normals::Options &opt, PointBufferPtr &buffer)
int main(int argc, char **argv)
std::shared_ptr< Model > ModelPtr
float getVoxelsize() const
std::shared_ptr< PointsetSurface< BaseVecT > > PointsetSurfacePtr
void getNormals(floatArr output_normals)
Get the resulting normals of the normal calculation. After calling "start".
static void saveModel(ModelPtr m, std::string file)
bool exportPointNormals() const