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