src/tools/lvr2_cl_normals/Main.cpp
Go to the documentation of this file.
1 
35 #include <boost/filesystem.hpp>
36 
38 
40 
46 
47 #include "lvr2/io/ModelFactory.hpp"
48 #include "lvr2/io/Timestamp.hpp"
49 #include "lvr2/io/IOUtils.hpp"
50 #include "Options.hpp"
51 
52 
53 using namespace lvr2;
54 
56 {
58  size_t num_points;
59 
60  floatArr points;
61  if (model && model->m_pointCloud )
62  {
63  num_points = model->m_pointCloud->numPoints();
64  points = model->m_pointCloud->getPointArray();
65  cout << timestamp << "Read " << num_points << " points from " << filename << endl;
66  }
67  else
68  {
69  cout << timestamp << "Warning: No point cloud data found in " << filename << endl;
70  return;
71  }
72 
73  floatArr normals = floatArr(new float[ num_points * 3 ]);
74 
75  cout << timestamp << "Constructing kd-tree..." << endl;
76  ClSurface gpu_surface(points, num_points);
77  cout << timestamp << "Finished kd-tree construction." << endl;
78 
79  gpu_surface.setKn(opt.kn());
80  gpu_surface.setKi(opt.ki());
81 
82  if(opt.useRansac())
83  {
84  gpu_surface.setMethod("RANSAC");
85  } else
86  {
87  gpu_surface.setMethod("PCA");
88  }
89  gpu_surface.setFlippoint(opt.flipx(), opt.flipy(), opt.flipz());
90 
91  cout << timestamp << "Start Normal Calculation..." << endl;
92  gpu_surface.calculateNormals();
93 
94  gpu_surface.getNormals(normals);
95  cout << timestamp << "Finished Normal Calculation. " << endl;
96 
97  buffer->setPointArray(points, num_points);
98  buffer->setNormalArray(normals, num_points);
99 
100  gpu_surface.freeGPU();
101 }
102 
104 {
105  // RECONSTRUCTION
106  // PointsetSurface
107  PointsetSurfacePtr<Vec> surface;
109  "FLANN",
110  opt.kn(),
111  opt.ki(),
112  opt.kd(),
113  1
114  ) );
115 
116 
117  // // Create an empty mesh
119 
120  float resolution = opt.getVoxelsize();
121 
122  auto grid = std::make_shared<PointsetGrid<Vec, BilinearFastBox<Vec>>>(
123  resolution,
124  surface,
125  surface->getBoundingBox(),
126  true,
127  true
128  );
129 
130  grid->calcDistanceValues();
131 
132  auto reconstruction = make_unique<FastReconstruction<Vec, BilinearFastBox<Vec>>>(grid);
133  reconstruction->getMesh(mesh);
134 
135 
137  MeshBufferPtr res = fin.apply(mesh);
138 
139  ModelPtr m( new Model( res ) );
140 
141  cout << timestamp << "Saving mesh." << endl;
142  ModelFactory::saveModel( m, "triangle_mesh.ply");
143 }
144 
145 int main(int argc, char** argv){
146 
147 
149  cout << opt << endl;
150 
151 
152  boost::filesystem::path inFile(opt.inputFile());
153 
154  if(boost::filesystem::is_directory(inFile))
155  {
156  vector<float> all_points;
157  vector<float> all_normals;
158 
159  boost::filesystem::directory_iterator lastFile;
160  for(boost::filesystem::directory_iterator it(inFile); it != lastFile; it++ )
161  {
162  boost::filesystem::path p = boost::filesystem::canonical(it->path());
163  string currentFile = p.filename().string();
164 
165  if(string(p.extension().string().c_str()) == ".3d")
166  {
167  // Check for naming convention "scanxxx.3d"
168  int num = 0;
169  if(sscanf(currentFile.c_str(), "scan%3d", &num))
170  {
171  cout << timestamp << "Processing " << p.string() << endl;
172  PointBufferPtr buffer(new PointBuffer);
173 
174  computeNormals(p.string(), opt, buffer);
175  transformPointCloudAndAppend(buffer, p, all_points, all_normals);
176 
177  }
178  }
179  }
180 
181  if(!opt.reconstruct() || opt.exportPointNormals() )
182  {
183  writePointsAndNormals(all_points, all_normals, opt.outputFile());
184  }
185 
186  if(opt.reconstruct() )
187  {
188  PointBufferPtr buffer(new PointBuffer);
189 
190  floatArr points = floatArr(&all_points[0]);
191  size_t num_points = all_points.size() / 3;
192 
193  floatArr normals = floatArr(&all_normals[0]);
194  size_t num_normals = all_normals.size() / 3;
195 
196  buffer->setPointArray(points, num_points);
197  buffer->setNormalArray(normals, num_normals);
198 
199  reconstructAndSave(buffer, opt);
200  }
201 
202  }
203  else
204  {
205  PointBufferPtr buffer(new PointBuffer);
206  computeNormals(opt.inputFile(), opt, buffer);
207 
208  if(!opt.reconstruct() || opt.exportPointNormals() )
209  {
210  ModelPtr out_model(new Model(buffer));
211  ModelFactory::saveModel(out_model, opt.outputFile());
212  }
213 
214  if(opt.reconstruct())
215  {
216  reconstructAndSave(buffer, opt);
217  }
218 
219  }
220 
221 
222 }
lvr2::floatArr
boost::shared_array< float > floatArr
Definition: DataStruct.hpp:133
lvr2::ModelFactory::saveModel
static void saveModel(ModelPtr m, std::string file)
Definition: ModelFactory.cpp:225
lvr2::transformPointCloudAndAppend
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...
Definition: IOUtils.cpp:40
cl_normals::Options::getVoxelsize
float getVoxelsize() const
Definition: src/tools/lvr2_cl_normals/Options.hpp:115
PointsetSurface.hpp
computeNormals
void computeNormals(string filename, cl_normals::Options &opt, PointBufferPtr &buffer)
Definition: src/tools/lvr2_cl_normals/Main.cpp:55
main
int main(int argc, char **argv)
Definition: src/tools/lvr2_cl_normals/Main.cpp:145
lvr2::PointBufferPtr
std::shared_ptr< PointBuffer > PointBufferPtr
Definition: PointBuffer.hpp:130
cl_normals::Options::flipz
float flipz() const
Definition: src/tools/lvr2_cl_normals/Options.hpp:95
p
SharedPointer p
Definition: ConvertShared.hpp:42
lvr2::PointBuffer
A class to handle point information with an arbitrarily large number of attribute channels....
Definition: PointBuffer.hpp:51
IOUtils.hpp
cl_normals::Options::outputFile
string outputFile() const
Definition: src/tools/lvr2_cl_normals/Options.hpp:63
cl_normals::Options::kn
int kn() const
Definition: src/tools/lvr2_cl_normals/Options.hpp:100
lvr2::Model
Definition: Model.hpp:51
HalfEdgeMesh.hpp
Options.hpp
ClSurface.hpp
cl_normals::Options::flipy
float flipy() const
Definition: src/tools/lvr2_cl_normals/Options.hpp:90
lvr2::ClSurface::setKi
void setKi(int ki)
Set the number of k nearest neighbors k-neighborhood for interpolation.
Definition: ClSurface.cpp:190
AdaptiveKSearchSurface.hpp
lvr2::SimpleFinalizer
Definition: FinalizeAlgorithms.hpp:68
lvr2::PointsetSurfacePtr
std::shared_ptr< PointsetSurface< BaseVecT > > PointsetSurfacePtr
Definition: PointsetSurface.hpp:161
lvr2::ClSurface::getNormals
void getNormals(floatArr output_normals)
Get the resulting normals of the normal calculation. After calling "start".
Definition: ClSurface.cpp:177
lvr2::ClSurface::setKn
void setKn(int kn)
Set the number of k nearest neighbors k-neighborhood.
Definition: ClSurface.cpp:185
FastReconstruction.hpp
lvr2::ClSurface
Definition: ClSurface.hpp:63
lvr2::AdaptiveKSearchSurface
A point cloud manager class that uses the STANN nearest neighbor search library to handle the data....
Definition: AdaptiveKSearchSurface.hpp:98
cl_normals::Options::kd
int kd() const
Definition: src/tools/lvr2_cl_normals/Options.hpp:110
BilinearFastBox.hpp
cl_normals::Options::flipx
float flipx() const
Definition: src/tools/lvr2_cl_normals/Options.hpp:85
cl_normals::Options::useRansac
bool useRansac() const
Definition: src/tools/lvr2_cl_normals/Options.hpp:75
scripts.normalize_multiple.filename
filename
Definition: normalize_multiple.py:60
lvr2::timestamp
static Timestamp timestamp
A global time stamp object for program runtime measurement.
Definition: Timestamp.hpp:116
PointsetGrid.hpp
cl_normals::Options::reconstruct
bool reconstruct() const
Definition: src/tools/lvr2_cl_normals/Options.hpp:125
argc
int argc
Definition: tests_high_five_parallel.cpp:27
cl_normals::Options
A class to parse the program options for the reconstruction executable.
Definition: src/tools/lvr2_cl_normals/Options.hpp:52
cl_normals::Options::ki
int ki() const
Definition: src/tools/lvr2_cl_normals/Options.hpp:105
cl_normals::Options::exportPointNormals
bool exportPointNormals() const
Definition: src/tools/lvr2_cl_normals/Options.hpp:130
lvr2
Definition: BaseBufferManipulators.hpp:39
cl_normals::Options::inputFile
string inputFile() const
Definition: src/tools/lvr2_cl_normals/Options.hpp:70
lvr2::ModelPtr
std::shared_ptr< Model > ModelPtr
Definition: Model.hpp:80
lvr2::MeshBufferPtr
std::shared_ptr< MeshBuffer > MeshBufferPtr
Definition: MeshBuffer.hpp:217
Timestamp.hpp
lvr2::writePointsAndNormals
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....
Definition: IOUtils.cpp:252
lvr2::ClSurface::calculateNormals
void calculateNormals()
Starts calculation the normals on GPU.
Definition: ClSurface.cpp:62
lvr2::ModelFactory::readModel
static ModelPtr readModel(std::string filename)
Definition: ModelFactory.cpp:65
ModelFactory.hpp
reconstructAndSave
void reconstructAndSave(PointBufferPtr &buffer, cl_normals::Options &opt)
Definition: src/tools/lvr2_cl_normals/Main.cpp:103
lvr2::ClSurface::setMethod
void setMethod(std::string method)
Set Method for normal calculation.
Definition: ClSurface.cpp:207
mesh
HalfEdgeMesh< Vec > mesh
Definition: src/tools/lvr2_gs_reconstruction/Main.cpp:26
lvr2::ClSurface::freeGPU
void freeGPU()
Definition: ClSurface.cpp:228
argv
char ** argv
Definition: tests_high_five_parallel.cpp:28
lvr2::ClSurface::setFlippoint
void setFlippoint(float v_x, float v_y, float v_z)
Set the viewpoint to orientate the normals.
Definition: ClSurface.cpp:200
lvr2::SimpleFinalizer::apply
MeshBufferPtr apply(const BaseMesh< BaseVecT > &mesh)
lvr2::HalfEdgeMesh
Half-edge data structure implementing the BaseMesh interface.
Definition: HalfEdgeMesh.hpp:70


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