HalfEdgeMesh.hpp
Go to the documentation of this file.
1 
28 /*
29  * HalfEdgeMesh.hpp
30  *
31  * @date 02.06.2017
32  * @author Lukas Kalbertodt <lukas.kalbertodt@gmail.com>
33  */
34 
35 #ifndef LVR2_GEOMETRY_HALFEDGEMESH_H_
36 #define LVR2_GEOMETRY_HALFEDGEMESH_H_
37 
38 #include <cstdint>
39 #include <utility>
41 #include <array>
42 #include <vector>
43 
44 using std::pair;
45 using std::array;
46 using std::vector;
47 using std::get;
48 using std::min;
49 
54 
55 #include "lvr2/io/MeshBuffer.hpp"
56 
57 namespace lvr2
58 {
59 
69 template<typename BaseVecT>
70 class HalfEdgeMesh : public BaseMesh<BaseVecT>
71 {
72 public:
73  using Edge = HalfEdge;
74  using Face = HalfEdgeFace;
76 
77  HalfEdgeMesh();
79 
80  // ========================================================================
81  // = Implementing the `BaseMesh` interface (see BaseMesh for docs)
82  // ========================================================================
83 
84  // We declare all methods as `final` to make devirtualization optimizations
85  // more likely and effective.
86  VertexHandle addVertex(BaseVecT pos) final;
88  void removeFace(FaceHandle handle) final;
90  VertexSplitResult splitVertex(VertexHandle vertexToBeSplitH);
92  vector<VertexHandle> findCommonNeigbours(VertexHandle vH1, VertexHandle vH2);
93  void flipEdge(EdgeHandle edgeH) final;
94  void splitVertex(EdgeHandle eH, VertexHandle vH, BaseVecT pos1, BaseVecT pos2);
95  std::pair<BaseVecT, float> triCircumCenter(FaceHandle faceH);
96 
97 
98  size_t numVertices() const final;
99  size_t numFaces() const final;
100  size_t numEdges() const final;
101 
102  bool containsVertex(VertexHandle vH) const;
103  bool containsFace(FaceHandle fH) const;
104  bool containsEdge(EdgeHandle eH) const;
105 
106  bool isBorderEdge(EdgeHandle handle) const;
107  bool isFlippable(EdgeHandle handle) const;
108 
109  Index nextVertexIndex() const;
110  Index nextFaceIndex() const;
111  Index nextEdgeIndex() const;
112 
113  BaseVecT getVertexPosition(VertexHandle handle) const final;
114  BaseVecT& getVertexPosition(VertexHandle handle) final;
115 
116  array<VertexHandle, 3> getVerticesOfFace(FaceHandle handle) const final;
117  array<EdgeHandle, 3> getEdgesOfFace(FaceHandle handle) const final;
118  void getNeighboursOfFace(FaceHandle handle, vector<FaceHandle>& facesOut) const final;
119  array<VertexHandle, 2> getVerticesOfEdge(EdgeHandle edgeH) const final;
120  array<OptionalFaceHandle, 2> getFacesOfEdge(EdgeHandle edgeH) const final;
121  void getFacesOfVertex(VertexHandle handle, vector<FaceHandle>& facesOut) const final;
122  void getEdgesOfVertex(VertexHandle handle, vector<EdgeHandle>& edgesOut) const final;
123  void getNeighboursOfVertex(VertexHandle handle, vector<VertexHandle>& verticesOut) const final;
127 
128  // Make sure all default methods from `BaseMesh` are visible
129  using BaseMesh<BaseVecT>::getFacesOfVertex;
130  using BaseMesh<BaseVecT>::getEdgesOfVertex;
131  using BaseMesh<BaseVecT>::getNeighboursOfVertex;
132 
133 
140 
141 
142  // ========================================================================
143  // = Other public methods
144  // ========================================================================
145 
146  bool debugCheckMeshIntegrity() const;
147 
148 private:
152 
153  // ========================================================================
154  // = Private helper methods
155  // ========================================================================
156  Edge& getE(HalfEdgeHandle handle);
157  const Edge& getE(HalfEdgeHandle handle) const;
158  Face& getF(FaceHandle handle);
159  const Face& getF(FaceHandle handle) const;
160  Vertex& getV(VertexHandle handle);
161  const Vertex& getV(VertexHandle handle) const;
162 
170 
177 
185 
194 
209 
210 
220  template <typename Visitor>
221  void circulateAroundVertex(VertexHandle vH, Visitor visitor) const;
222 
230  template <typename Visitor>
231  void circulateAroundVertex(HalfEdgeHandle startEdgeH, Visitor visitor) const;
232 
240  template <typename Pred>
242 
250  template <typename Pred>
251  OptionalHalfEdgeHandle findEdgeAroundVertex(HalfEdgeHandle startEdgeH, Pred pred) const;
252 
256  array<HalfEdgeHandle, 3> getInnerEdges(FaceHandle handle) const;
257 
258  // ========================================================================
259  // = Friends
260  // ========================================================================
261  template<typename> friend class HemEdgeIterator;
262 };
263 
265 template<typename HandleT, typename ElemT>
266 class HemFevIterator : public MeshHandleIterator<HandleT>
267 {
268 public:
269  HemFevIterator(StableVectorIterator<HandleT, ElemT> iterator) : m_iterator(iterator) {};
270  HemFevIterator& operator++();
271  bool operator==(const MeshHandleIterator<HandleT>& other) const;
272  bool operator!=(const MeshHandleIterator<HandleT>& other) const;
273  HandleT operator*() const;
274 
275 private:
277 };
278 
279 template<typename BaseVecT>
280 class HemEdgeIterator : public MeshHandleIterator<EdgeHandle>
281 {
282 public:
286  ) : m_iterator(iterator), m_mesh(mesh) {};
287 
288  HemEdgeIterator& operator++();
289  bool operator==(const MeshHandleIterator<EdgeHandle>& other) const;
290  bool operator!=(const MeshHandleIterator<EdgeHandle>& other) const;
291  EdgeHandle operator*() const;
292 
293 private:
296 };
297 
298 } // namespace lvr2
299 
300 #include "lvr2/geometry/HalfEdgeMesh.tcc"
301 
302 #endif /* LVR2_GEOMETRY_HALFEDGEMESH_H_ */
lvr2::HalfEdgeMesh::circulateAroundVertex
void circulateAroundVertex(VertexHandle vH, Visitor visitor) const
Circulates around the vertex vH, calling the visitor for each ingoing edge of the vertex.
lvr2::HalfEdgeMesh::getE
Edge & getE(HalfEdgeHandle handle)
lvr2::HalfEdgeMesh::numVertices
size_t numVertices() const final
Returns the number of vertices in the mesh.
lvr2::HemEdgeIterator::m_iterator
StableVectorIterator< HalfEdgeHandle, HalfEdge > m_iterator
Definition: HalfEdgeMesh.hpp:294
lvr2::HalfEdgeMesh::isBorderEdge
bool isBorderEdge(EdgeHandle handle) const
Determines wheter the given edge is an border edge, i.e., if it is connected to two faces or not.
lvr2::MeshHandleIterator
An iterator for handles in the BaseMesh.
Definition: BaseMesh.hpp:61
lvr2::HalfEdgeHandle
Handle to access half edges of the HEM.
Definition: HalfEdge.hpp:52
lvr2::HalfEdgeMesh::numFaces
size_t numFaces() const final
Returns the number of faces in the mesh.
lvr2::HalfEdgeMesh::getOppositeEdge
OptionalEdgeHandle getOppositeEdge(FaceHandle faceH, VertexHandle vertexH) const
Get the optional edge handle of the edge lying on the vertex's opposite site.
lvr2::HemEdgeIterator
Definition: HalfEdgeMesh.hpp:280
lvr2::StableVectorIterator
Iterator over handles in this vector, which skips deleted elements.
Definition: StableVector.hpp:61
lvr2::HalfEdgeMesh::HalfEdgeMesh
HalfEdgeMesh()
lvr2::HalfEdgeMesh::findEdgeAroundVertex
OptionalHalfEdgeHandle findEdgeAroundVertex(VertexHandle vH, Pred pred) const
Iterates over all ingoing edges of one vertex, returning the first edge that satisfies the given pred...
lvr2::FaceHandle
Handle to access faces of the mesh.
Definition: Handles.hpp:140
lvr2::HalfEdgeMesh::edgesEnd
MeshHandleIteratorPtr< EdgeHandle > edgesEnd() const final
Returns an iterator to the element following the last edge of this mesh.
lvr2::HalfEdgeMesh::getInnerEdges
array< HalfEdgeHandle, 3 > getInnerEdges(FaceHandle handle) const
Get inner edges in counter clockwise order.
lvr2::HalfEdgeFace
Represents a face in the HEM data structure.
Definition: HalfEdgeFace.hpp:49
lvr2::HalfEdgeMesh::nextEdgeIndex
Index nextEdgeIndex() const
Returns the handle index which would be assigned to the next edge that is created....
lvr2::HalfEdgeMesh::getNeighboursOfVertex
void getNeighboursOfVertex(VertexHandle handle, vector< VertexHandle > &verticesOut) const final
lvr2::HalfEdgeMesh::splitEdge
EdgeSplitResult splitEdge(EdgeHandle edgeH)
lvr2::OptionalVertexHandle
Semantically equivalent to boost::optional<VertexHandle>
Definition: Handles.hpp:176
lvr2::HalfEdgeMesh::debugCheckMeshIntegrity
bool debugCheckMeshIntegrity() const
lvr2::HalfEdgeMesh::getFacesOfEdge
array< OptionalFaceHandle, 2 > getFacesOfEdge(EdgeHandle edgeH) const final
Get the two faces of an edge.
lvr2::HalfEdgeMesh::getEdgesOfFace
array< EdgeHandle, 3 > getEdgesOfFace(FaceHandle handle) const final
Get the three edges surrounding the given face.
lvr2::HalfEdgeMesh::getFacesOfVertex
void getFacesOfVertex(VertexHandle handle, vector< FaceHandle > &facesOut) const final
lvr2::HalfEdge
Definition: HalfEdge.hpp:74
lvr2::HalfEdgeMesh::nextVertexIndex
Index nextVertexIndex() const
Returns the handle index which would be assigned to the next vertex that is created....
lvr2::HemFevIterator
Implementation of the MeshHandleIterator for the HalfEdgeMesh.
Definition: HalfEdgeMesh.hpp:266
BaseMesh.hpp
HalfEdgeVertex.hpp
lvr2::HalfEdgeMesh::getOppositeVertex
OptionalVertexHandle getOppositeVertex(FaceHandle faceH, EdgeHandle edgeH) const
Get the optional vertex handle of the vertex lying on the edge's opposite site.
lvr2::HalfEdgeMesh::facesEnd
MeshHandleIteratorPtr< FaceHandle > facesEnd() const final
Returns an iterator to the element following the last face of this mesh.
lvr2::HemFevIterator::m_iterator
StableVectorIterator< HandleT, ElemT > m_iterator
Definition: HalfEdgeMesh.hpp:276
lvr2::HalfEdgeMesh::findOrCreateEdgeBetween
HalfEdgeHandle findOrCreateEdgeBetween(VertexHandle fromH, VertexHandle toH)
Attempts to find an edge between the given vertices and, if none is found, creates a new edge with ad...
lvr2::HalfEdgeMesh::getVertexPosition
BaseVecT getVertexPosition(VertexHandle handle) const final
Get the position of the given vertex.
lvr2::HalfEdgeMesh::getEdgesOfVertex
void getEdgesOfVertex(VertexHandle handle, vector< EdgeHandle > &edgesOut) const final
lvr2::HalfEdgeMesh::findCommonNeigbours
vector< VertexHandle > findCommonNeigbours(VertexHandle vH1, VertexHandle vH2)
lvr2::EdgeHandle
Handle to access edges of the mesh.
Definition: Handles.hpp:134
lvr2::HalfEdgeMesh::getVerticesOfEdge
array< VertexHandle, 2 > getVerticesOfEdge(EdgeHandle edgeH) const final
Get the two vertices of an edge.
lvr2::OptionalEdgeHandle
Semantically equivalent to boost::optional<EdgeHandle>
Definition: Handles.hpp:164
lvr2::VertexSplitResult
Definition: BaseMesh.hpp:687
lvr2::HalfEdgeMesh::getV
Vertex & getV(VertexHandle handle)
lvr2::HalfEdgeMesh::edgesBegin
MeshHandleIteratorPtr< EdgeHandle > edgesBegin() const final
Returns an iterator to the first edge of this mesh.
lvr2::HalfEdgeMesh::addVertex
VertexHandle addVertex(BaseVecT pos) final
Adds a vertex with the given position to the mesh.
lvr2::HalfEdgeMesh::getOppositeFace
OptionalFaceHandle getOppositeFace(FaceHandle faceH, VertexHandle vertexH) const
Get the optional face handle of the neighboring face lying on the vertex's opposite site.
lvr2::HalfEdgeMesh::getVerticesOfFace
array< VertexHandle, 3 > getVerticesOfFace(FaceHandle handle) const final
Get the three vertices surrounding the given face.
lvr2::OptionalFaceHandle
Semantically equivalent to boost::optional<FaceHandle>
Definition: Handles.hpp:170
lvr2::StableVector
A vector which guarantees stable indices and features O(1) deletion.
Definition: StableVector.hpp:104
lvr2::OptionalHalfEdgeHandle
Semantically equivalent to boost::optional<HalfEdgeHandle>
Definition: HalfEdge.hpp:66
StableVector.hpp
lvr2::HalfEdgeMesh::collapseEdge
EdgeCollapseResult collapseEdge(EdgeHandle edgeH) final
Merges the two vertices connected by the given edge.
lvr2::VertexHandle
Handle to access vertices of the mesh.
Definition: Handles.hpp:146
lvr2::HalfEdgeMesh::nextFaceIndex
Index nextFaceIndex() const
Returns the handle index which would be assigned to the next face that is created....
lvr2::HalfEdgeMesh::splitVertex
VertexSplitResult splitVertex(VertexHandle vertexToBeSplitH)
lvr2::HemEdgeIterator::m_mesh
const HalfEdgeMesh< BaseVecT > & m_mesh
Definition: HalfEdgeMesh.hpp:295
HalfEdgeFace.hpp
lvr2::HalfEdgeMesh::numEdges
size_t numEdges() const final
Returns the number of edges in the mesh.
lvr2::HalfEdgeMesh::m_edges
StableVector< HalfEdgeHandle, Edge > m_edges
Definition: HalfEdgeMesh.hpp:149
MeshBuffer.hpp
lvr2::EdgeCollapseResult
Definition: BaseMesh.hpp:671
lvr2::HalfEdgeMesh::m_faces
StableVector< FaceHandle, Face > m_faces
Definition: HalfEdgeMesh.hpp:150
HalfEdge.hpp
lvr2::HalfEdgeMesh::facesBegin
MeshHandleIteratorPtr< FaceHandle > facesBegin() const final
Returns an iterator to the first face of this mesh.
lvr2::HalfEdgeMesh::addFace
FaceHandle addFace(VertexHandle v1H, VertexHandle v2H, VertexHandle v3H) final
Creates a face connecting the three given vertices.
lvr2::HalfEdgeMesh::edgeBetween
OptionalHalfEdgeHandle edgeBetween(VertexHandle fromH, VertexHandle toH)
Given two vertices, find the edge pointing from one to the other.
lvr2::HalfEdgeMesh::getF
Face & getF(FaceHandle handle)
lvr2::HalfEdgeMesh::flipEdge
void flipEdge(EdgeHandle edgeH) final
Performs the edge flip operation.
lvr2::HalfEdgeMesh::m_vertices
StableVector< VertexHandle, Vertex > m_vertices
Definition: HalfEdgeMesh.hpp:151
lvr2::HalfEdgeMesh::containsVertex
bool containsVertex(VertexHandle vH) const
Checks if the given vertex is part of this mesh.
lvr2
Definition: BaseBufferManipulators.hpp:39
lvr2::HemFevIterator::HemFevIterator
HemFevIterator(StableVectorIterator< HandleT, ElemT > iterator)
Definition: HalfEdgeMesh.hpp:269
lvr2::HalfEdgeMesh::triCircumCenter
std::pair< BaseVecT, float > triCircumCenter(FaceHandle faceH)
lvr2::HalfEdgeMesh::addEdgePair
pair< HalfEdgeHandle, HalfEdgeHandle > addEdgePair(VertexHandle v1H, VertexHandle v2H)
Adds a new, incomplete edge-pair.
lvr2::HemEdgeIterator::HemEdgeIterator
HemEdgeIterator(StableVectorIterator< HalfEdgeHandle, HalfEdge > iterator, const HalfEdgeMesh< BaseVecT > &mesh)
Definition: HalfEdgeMesh.hpp:283
lvr2::MeshBufferPtr
std::shared_ptr< MeshBuffer > MeshBufferPtr
Definition: MeshBuffer.hpp:217
lvr2::HalfEdgeMesh::halfToFullEdgeHandle
EdgeHandle halfToFullEdgeHandle(HalfEdgeHandle handle) const
Converts a half edge handle to a full edge handle.
lvr2::BaseMesh
Interface for triangle-meshes with adjacency information.
Definition: BaseMesh.hpp:140
lvr2::HalfEdgeMesh::containsFace
bool containsFace(FaceHandle fH) const
Checks if the given face is part of this mesh.
lvr2::HalfEdgeVertex
Represents a vertex in the HEM data structure.
Definition: HalfEdgeVertex.hpp:50
lvr2::Index
uint32_t Index
Datatype used as index for each vertex, face and edge.
Definition: Handles.hpp:96
lvr2::HalfEdgeMesh::containsEdge
bool containsEdge(EdgeHandle eH) const
Checks if the given edge is part of this mesh.
lvr2::HalfEdgeMesh::isFlippable
bool isFlippable(EdgeHandle handle) const
Determines whether or not the given edge can be flipped without destroying the mesh.
lvr2::EdgeSplitResult
Definition: BaseMesh.hpp:696
mesh
HalfEdgeMesh< Vec > mesh
Definition: src/tools/lvr2_gs_reconstruction/Main.cpp:26
lvr2::MeshHandleIteratorPtr
A wrapper for the MeshHandleIterator to save beloved future programmers from dereferencing too much <...
Definition: BaseMesh.hpp:81
lvr2::HalfEdgeMesh::removeFace
void removeFace(FaceHandle handle) final
Removes the given face and all (if not connected to any other face/edge/vertex) connected edges and v...
lvr2::operator*
BaseVector< CoordType > operator*(const Eigen::Matrix< Scalar, 4, 4 > &mat, const BaseVector< CoordType > &normal)
Multiplication operator to support transformation with Eigen matrices. Rotates the normal,...
Definition: BaseVector.hpp:249
lvr2::HalfEdgeMesh::verticesBegin
MeshHandleIteratorPtr< VertexHandle > verticesBegin() const final
Returns an iterator to the first vertex of this mesh.
lvr2::HalfEdgeMesh::verticesEnd
MeshHandleIteratorPtr< VertexHandle > verticesEnd() const final
Returns an iterator to the element following the last vertex of this mesh.
lvr2::HalfEdgeMesh
Half-edge data structure implementing the BaseMesh interface.
Definition: HalfEdgeMesh.hpp:70
lvr2::HalfEdgeMesh::getNeighboursOfFace
void getNeighboursOfFace(FaceHandle handle, vector< FaceHandle > &facesOut) const final


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