DMCReconstruction.hpp
Go to the documentation of this file.
1 
28  /*
29  * DMCReconstruction.hpp
30  *
31  * Created on: 18.01.2019
32  * Author: Benedikt Schumacher
33  */
34 
35 #ifndef DMCReconstruction_HPP_
36 #define DMCReconstruction_HPP_
37 
44 #include "lvr2/io/Progress.hpp"
45 #include "DMCVecPointHandle.hpp"
46 
47 #include "Octree.hpp"
48 #include "DualOctree.hpp"
49 #include "Location.hh"
51 
52 namespace lvr2
53 {
54 
55 struct my_dummy
56 {
58  int next = -1;
59 };
60 
66 template<typename BaseVecT, typename BoxT>
67 class DMCReconstruction : public FastReconstructionBase<BaseVecT>, public PointsetMeshGenerator<BaseVecT>
68 {
69 public:
70 
83  bool dual,
84  int maxLevel,
85  float maxError);
86 
90  virtual ~DMCReconstruction();
91 
97  virtual void getMesh(BaseMesh<BaseVecT> &mesh);
98 
99  virtual void getMesh(
102  vector<unsigned int>& duplicates,
103  float comparePrecision
104  );
105 
106 protected:
107 
117  CellHandle &cell,
118  int cells,
120  char pos);
121 
131  void buildTree(
133  int levels,
134  bool dual);
135 
144 
158  CellHandle ch,
159  int cells,
160  float max_bb_width,
161  uint pos,
162  int onEdge,
163  BaseVecT &feature);
164 
173  void getRotationMatrix(
174  float matrix[9],
175  BaseVecT v1,
176  BaseVecT v2,
177  BaseVecT v3);
178 
187  float getDistance(BaseVecT p,
188  BaseVecT v1,
189  BaseVecT v2,
190  BaseVecT v3);
191 
199  float getDistance(BaseVecT p,
200  BaseVecT v1,
201  BaseVecT v2);
202 
209  float getDistance(BaseVecT v1,
210  BaseVecT v2);
211 
219  float edgeEquation(BaseVecT p,
220  BaseVecT v1,
221  BaseVecT v2);
222 
229  void matrixDotVector(float* matrix,
230  BaseVecT* vector);
231 
241  int cells,
242  short level);
243 
250 
251  // Indicator whether the point fitting shoulb be done on dual cells
252  bool m_dual;
253 
254  // The maximum allowed level for the octree
256 
257  // The max allowed arror between points and surfaces
258  float m_maxError;
259 
260  // Sizes of Boundig Box
261  BaseVecT bb_min;
262  BaseVecT bb_max;
263  float bb_size[3];
265 
266  // Center of the bounding box.
268 
269  // Count of the octree leaves.
271 
272  // Global progress bar.
274 
275  // Pointer to the new Octree
277 
278  // PointHandler
279  unique_ptr<DMCPointHandle<BaseVecT>> m_pointHandler;
280 
281  // just for visualization
282  std::vector< BaseVecT > dualVertices;
283 };
284 } // namespace lvr2
285 
286 #include "DMCReconstruction.tcc"
287 
288 #endif /* DMCReconstruction_HPP_ */
lvr2::ProgressBar
Definition: Progress.hpp:68
BaseVector.hpp
lvr2::DMCReconstruction::m_dual
bool m_dual
Definition: DMCReconstruction.hpp:252
PointsetSurface.hpp
lvr2::DMCReconstruction::getDualLeaf
DualLeaf< BaseVecT, BoxT > * getDualLeaf(CellHandle &cell, int cells, C_Octree< BaseVecT, BoxT, my_dummy > &octree, char pos)
Builds a dual cell at given position.
lvr2::DMCReconstruction::m_maxLevel
int m_maxLevel
Definition: DMCReconstruction.hpp:255
lvr2::DMCReconstruction::matrixDotVector
void matrixDotVector(float *matrix, BaseVecT *vector)
Performs a matrix multiplication.
lvr2::DMCReconstruction::getDistance
float getDistance(BaseVecT p, BaseVecT v1, BaseVecT v2, BaseVecT v3)
Calculates the distance between a point and a triangle.
lvr2::my_dummy
Definition: DMCReconstruction.hpp:55
lvr2::DMCReconstruction::DMCReconstruction
DMCReconstruction(PointsetSurfacePtr< BaseVecT > surface, BoundingBox< BaseVecT > bb, bool dual, int maxLevel, float maxError)
Constructor.
lvr2::DMCReconstruction::octree
C_Octree< BaseVecT, BoxT, my_dummy > * octree
Definition: DMCReconstruction.hpp:276
p
SharedPointer p
Definition: ConvertShared.hpp:42
lvr2::DMCReconstruction::bb_max
BaseVecT bb_max
Definition: DMCReconstruction.hpp:262
lvr2::DMCReconstruction::~DMCReconstruction
virtual ~DMCReconstruction()
Destructor.
Octree.hpp
lvr2::DMCReconstruction::getRotationMatrix
void getRotationMatrix(float matrix[9], BaseVecT v1, BaseVecT v2, BaseVecT v3)
Calculates a rotation matrix for a triangle that rotates it into xy.
MCTable.hpp
lvr2::DMCReconstruction::m_leaves
uint m_leaves
Definition: DMCReconstruction.hpp:270
lvr2::my_dummy::next
int next
Definition: DMCReconstruction.hpp:58
lvr2::DMCReconstruction::detectVertexForDualCell
void detectVertexForDualCell(C_Octree< BaseVecT, BoxT, my_dummy > &octree, CellHandle ch, int cells, float max_bb_width, uint pos, int onEdge, BaseVecT &feature)
Calculates the position of a aspecific point in a dual cell.
lvr2::PointsetSurfacePtr
std::shared_ptr< PointsetSurface< BaseVecT > > PointsetSurfacePtr
Definition: PointsetSurface.hpp:161
lvr2::DMCReconstruction::m_progressBar
ProgressBar * m_progressBar
Definition: DMCReconstruction.hpp:273
lvr2::my_dummy::location
Location location
Definition: DMCReconstruction.hpp:57
lvr2::C_Octree
Definition: Octree.hpp:26
FastReconstruction.hpp
DMCVecPointHandle.hpp
lvr2::DMCReconstruction::drawOctree
void drawOctree(C_Octree< BaseVecT, BoxT, my_dummy > &parent)
Saves the octree as wireframe. WORKS ONLY SINGLE THREADED!
LocalApproximation.hpp
lvr2::PointsetMeshGenerator
Interface class for surface reconstruction algorithms that generate triangle meshes from point set su...
Definition: PointsetMeshGenerator.hpp:50
lvr2::DMCReconstruction::m_pointHandler
unique_ptr< DMCPointHandle< BaseVecT > > m_pointHandler
Definition: DMCReconstruction.hpp:279
Progress.hpp
lvr2::DMCReconstruction
A surface reconstruction object that implements the standard marching cubes algorithm using a octree ...
Definition: DMCReconstruction.hpp:67
lvr2::DMCReconstruction::bb_size
float bb_size[3]
Definition: DMCReconstruction.hpp:263
lvr2::Location
Definition: Location.hh:24
lvr2::DMCReconstruction::bb_longestSide
float bb_longestSide
Definition: DMCReconstruction.hpp:264
lvr2::DMCReconstruction::getSurface
void getSurface(BaseMesh< BaseVecT > &mesh, DualLeaf< BaseVecT, BoxT > *leaf, int cells, short level)
Performs a local reconstruction according to the standard Marching Cubes table from Paul Bourke.
lvr2::BoundingBox
A dynamic bounding box class.
Definition: BoundingBox.hpp:49
DualOctree.hpp
PointsetMeshGenerator.hpp
lvr2::DMCReconstruction::buildTree
void buildTree(C_Octree< BaseVecT, BoxT, my_dummy > &parent, int levels, bool dual)
Builds a tree level respectively creates the child nodes of a root node.
lvr2::DualLeaf
Definition: DualOctree.hpp:45
lvr2::DMCReconstruction::getMesh
virtual void getMesh(BaseMesh< BaseVecT > &mesh)
Returns the surface reconstruction of the given point set.
lvr2::DMCReconstruction::traverseTree
void traverseTree(BaseMesh< BaseVecT > &mesh, C_Octree< BaseVecT, BoxT, my_dummy > &octree)
Traverses the octree and insert for each leaf the getSurface-function into the thread pool.
lvr2::DMCReconstruction::bb_min
BaseVecT bb_min
Definition: DMCReconstruction.hpp:261
lvr2
Definition: BaseBufferManipulators.hpp:39
lvr2::DMCReconstruction::edgeEquation
float edgeEquation(BaseVecT p, BaseVecT v1, BaseVecT v2)
Calculates whether the given vertex lies left, right or on the given line.
Location.hh
lvr2::BaseMesh
Interface for triangle-meshes with adjacency information.
Definition: BaseMesh.hpp:140
lvr2::DMCReconstruction::dualVertices
std::vector< BaseVecT > dualVertices
Definition: DMCReconstruction.hpp:282
uint
unsigned int uint
Definition: Model.hpp:46
lvr2::CellHandle
Definition: CellHandle.hh:22
lvr2::DMCReconstruction::m_boundingBoxCenter
BaseVecT m_boundingBoxCenter
Definition: DMCReconstruction.hpp:267
mesh
HalfEdgeMesh< Vec > mesh
Definition: src/tools/lvr2_gs_reconstruction/Main.cpp:26
BoundingBox.hpp
lvr2::FastReconstructionBase
Definition: FastReconstruction.hpp:61
lvr2::DMCReconstruction::m_maxError
float m_maxError
Definition: DMCReconstruction.hpp:258


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:23