35 #ifndef LVR2_GEOMETRY_HALFEDGEMESH_H_ 36 #define LVR2_GEOMETRY_HALFEDGEMESH_H_ 69 template<
typename BaseVecT>
122 void getEdgesOfVertex(VertexHandle handle, vector<EdgeHandle>& edgesOut) const final;
157 const
Edge&
getE(HalfEdgeHandle handle) const;
159 const
Face&
getF(FaceHandle handle) const;
161 const
Vertex&
getV(VertexHandle handle) const;
208 pair<HalfEdgeHandle, HalfEdgeHandle>
addEdgePair(VertexHandle v1H, VertexHandle v2H);
220 template <typename Visitor>
230 template <typename Visitor>
240 template <typename Pred>
250 template <typename Pred>
256 array<HalfEdgeHandle, 3>
getInnerEdges(FaceHandle handle) const;
265 template<typename HandleT, typename ElemT>
279 template<
typename BaseVecT>
286 ) : m_iterator(iterator), m_mesh(mesh) {};
300 #include "lvr2/geometry/HalfEdgeMesh.tcc" A wrapper for the MeshHandleIterator to save beloved future programmers from dereferencing too much <...
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.
std::shared_ptr< MeshBuffer > MeshBufferPtr
OptionalEdgeHandle getOppositeEdge(FaceHandle faceH, VertexHandle vertexH) const
Get the optional edge handle of the edge lying on the vertex'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.
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.
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'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>
array< EdgeHandle, 3 > getEdgesOfFace(FaceHandle handle) const final
Get the three edges surrounding the given face.
Interface for triangle-meshes with adjacency information.
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'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>
std::pair< BaseVecT, float > triCircumCenter(FaceHandle faceH)
An iterator for handles in the BaseMesh.
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>
Handle to access half edges of the HEM.
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...
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.
VertexHandle addVertex(BaseVecT pos) final
Adds a vertex with the given position to the mesh.
Semantically equivalent to boost::optional<EdgeHandle>