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;
124  OptionalFaceHandle getOppositeFace(FaceHandle faceH, VertexHandle vertexH) const;
125  OptionalEdgeHandle getOppositeEdge(FaceHandle faceH, VertexHandle vertexH) const;
126  OptionalVertexHandle getOppositeVertex(FaceHandle faceH, EdgeHandle edgeH) const;
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 
134  MeshHandleIteratorPtr<VertexHandle> verticesBegin() const final;
135  MeshHandleIteratorPtr<VertexHandle> verticesEnd() const final;
138  MeshHandleIteratorPtr<EdgeHandle> edgesBegin() const final;
139  MeshHandleIteratorPtr<EdgeHandle> edgesEnd() const final;
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 
169  EdgeHandle halfToFullEdgeHandle(HalfEdgeHandle handle) const;
170 
176  OptionalHalfEdgeHandle edgeBetween(VertexHandle fromH, VertexHandle toH);
177 
184  HalfEdgeHandle findOrCreateEdgeBetween(VertexHandle fromH, VertexHandle toH);
185 
193  HalfEdgeHandle findOrCreateEdgeBetween(VertexHandle fromH, VertexHandle toH, bool& added);
194 
208  pair<HalfEdgeHandle, HalfEdgeHandle> addEdgePair(VertexHandle v1H, VertexHandle v2H);
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>
241  OptionalHalfEdgeHandle findEdgeAroundVertex(VertexHandle vH, Pred pred) const;
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_ */
A wrapper for the MeshHandleIterator to save beloved future programmers from dereferencing too much <...
Definition: BaseMesh.hpp:81
OptionalHalfEdgeHandle edgeBetween(VertexHandle fromH, VertexHandle toH)
Given two vertices, find the edge pointing from one to the other.
A vector which guarantees stable indices and features O(1) deletion.
StableVector< HalfEdgeHandle, Edge > m_edges
size_t numVertices() const final
Returns the number of vertices in the mesh.
bool containsEdge(EdgeHandle eH) const
Checks if the given edge is part of this mesh.
bool containsVertex(VertexHandle vH) const
Checks if the given vertex is part of this mesh.
Handle to access vertices of the mesh.
Definition: Handles.hpp:146
HalfEdgeMesh< Vec > mesh
std::shared_ptr< MeshBuffer > MeshBufferPtr
Definition: MeshBuffer.hpp:217
OptionalEdgeHandle getOppositeEdge(FaceHandle faceH, VertexHandle vertexH) const
Get the optional edge handle of the edge lying on the vertex&#39;s opposite site.
MeshHandleIteratorPtr< EdgeHandle > edgesBegin() const final
Returns an iterator to the first edge of this mesh.
bool containsFace(FaceHandle fH) const
Checks if the given face is part of this mesh.
EdgeCollapseResult collapseEdge(EdgeHandle edgeH) final
Merges the two vertices connected by the given edge.
MeshHandleIteratorPtr< EdgeHandle > edgesEnd() const final
Returns an iterator to the element following the last edge of this mesh.
array< HalfEdgeHandle, 3 > getInnerEdges(FaceHandle handle) const
Get inner edges in counter clockwise order.
Represents a face in the HEM data structure.
Handle to access edges of the mesh.
Definition: Handles.hpp:134
array< VertexHandle, 2 > getVerticesOfEdge(EdgeHandle edgeH) const final
Get the two vertices of an edge.
uint32_t Index
Datatype used as index for each vertex, face and edge.
Definition: Handles.hpp:96
HemFevIterator(StableVectorIterator< HandleT, ElemT > iterator)
void getFacesOfVertex(VertexHandle handle, vector< FaceHandle > &facesOut) const final
vector< VertexHandle > findCommonNeigbours(VertexHandle vH1, VertexHandle vH2)
OptionalVertexHandle getOppositeVertex(FaceHandle faceH, EdgeHandle edgeH) const
Get the optional vertex handle of the vertex lying on the edge&#39;s opposite site.
Edge & getE(HalfEdgeHandle handle)
Implementation of the MeshHandleIterator for the HalfEdgeMesh.
void getEdgesOfVertex(VertexHandle handle, vector< EdgeHandle > &edgesOut) const final
Iterator over handles in this vector, which skips deleted elements.
Semantically equivalent to boost::optional<VertexHandle>
Definition: Handles.hpp:176
array< EdgeHandle, 3 > getEdgesOfFace(FaceHandle handle) const final
Get the three edges surrounding the given face.
Interface for triangle-meshes with adjacency information.
Definition: BaseMesh.hpp:140
Index nextEdgeIndex() const
Returns the handle index which would be assigned to the next edge that is created. This method is mainly useful for manually iterating over all possible handles. As handles are strictly increasing, all edges currently in this mesh have a handle index smaller than what this method returns.
StableVector< VertexHandle, Vertex > m_vertices
OptionalFaceHandle getOppositeFace(FaceHandle faceH, VertexHandle vertexH) const
Get the optional face handle of the neighboring face lying on the vertex&#39;s opposite site...
array< VertexHandle, 3 > getVerticesOfFace(FaceHandle handle) const final
Get the three vertices surrounding the given face.
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...
void flipEdge(EdgeHandle edgeH) final
Performs the edge flip operation.
FaceHandle addFace(VertexHandle v1H, VertexHandle v2H, VertexHandle v3H) final
Creates a face connecting the three given vertices.
EdgeSplitResult splitEdge(EdgeHandle edgeH)
HemEdgeIterator(StableVectorIterator< HalfEdgeHandle, HalfEdge > iterator, const HalfEdgeMesh< BaseVecT > &mesh)
StableVectorIterator< HalfEdgeHandle, HalfEdge > m_iterator
MeshHandleIteratorPtr< FaceHandle > facesBegin() const final
Returns an iterator to the first face of this mesh.
void circulateAroundVertex(VertexHandle vH, Visitor visitor) const
Circulates around the vertex vH, calling the visitor for each ingoing edge of the vertex...
Half-edge data structure implementing the BaseMesh interface.
bool debugCheckMeshIntegrity() const
size_t numFaces() const final
Returns the number of faces in the mesh.
Represents a vertex in the HEM data structure.
size_t numEdges() const final
Returns the number of edges in the mesh.
Semantically equivalent to boost::optional<FaceHandle>
Definition: Handles.hpp:170
std::pair< BaseVecT, float > triCircumCenter(FaceHandle faceH)
An iterator for handles in the BaseMesh.
Definition: BaseMesh.hpp:61
const HalfEdgeMesh< BaseVecT > & m_mesh
void getNeighboursOfFace(FaceHandle handle, vector< FaceHandle > &facesOut) const final
Index nextFaceIndex() const
Returns the handle index which would be assigned to the next face that is created. This method is mainly useful for manually iterating over all possible handles. As handles are strictly increasing, all faces currently in this mesh have a handle index smaller than what this method returns.
Semantically equivalent to boost::optional<HalfEdgeHandle>
Definition: HalfEdge.hpp:66
Handle to access half edges of the HEM.
Definition: HalfEdge.hpp:52
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...
VertexSplitResult splitVertex(VertexHandle vertexToBeSplitH)
Face & getF(FaceHandle handle)
StableVectorIterator< HandleT, ElemT > m_iterator
OptionalHalfEdgeHandle findEdgeAroundVertex(VertexHandle vH, Pred pred) const
Iterates over all ingoing edges of one vertex, returning the first edge that satisfies the given pred...
Vertex & getV(VertexHandle handle)
MeshHandleIteratorPtr< VertexHandle > verticesEnd() const final
Returns an iterator to the element following the last vertex of this mesh.
MeshHandleIteratorPtr< FaceHandle > facesEnd() const final
Returns an iterator to the element following the last face of this mesh.
void removeFace(FaceHandle handle) final
Removes the given face and all (if not connected to any other face/edge/vertex) connected edges and v...
EdgeHandle halfToFullEdgeHandle(HalfEdgeHandle handle) const
Converts a half edge handle to a full edge handle.
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
Index nextVertexIndex() const
Returns the handle index which would be assigned to the next vertex that is created. This method is mainly useful for manually iterating over all possible handles. As handles are strictly increasing, all vertices currently in this mesh have a handle index smaller than what this method returns.
MeshHandleIteratorPtr< VertexHandle > verticesBegin() const final
Returns an iterator to the first vertex of this mesh.
StableVector< FaceHandle, Face > m_faces
void getNeighboursOfVertex(VertexHandle handle, vector< VertexHandle > &verticesOut) const final
BaseVecT getVertexPosition(VertexHandle handle) const final
Get the position of the given vertex.
pair< HalfEdgeHandle, HalfEdgeHandle > addEdgePair(VertexHandle v1H, VertexHandle v2H)
Adds a new, incomplete edge-pair.
array< OptionalFaceHandle, 2 > getFacesOfEdge(EdgeHandle edgeH) const final
Get the two faces of an edge.
bool isFlippable(EdgeHandle handle) const
Determines whether or not the given edge can be flipped without destroying the mesh.
Handle to access faces of the mesh.
Definition: Handles.hpp:140
VertexHandle addVertex(BaseVecT pos) final
Adds a vertex with the given position to the mesh.
Semantically equivalent to boost::optional<EdgeHandle>
Definition: Handles.hpp:164


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 Mon Feb 28 2022 22:46:06