Go to the documentation of this file.
35 #ifndef LVR2_GEOMETRY_HALFEDGEMESH_H_
36 #define LVR2_GEOMETRY_HALFEDGEMESH_H_
69 template<
typename BaseVecT>
220 template <typename Visitor>
230 template <typename Visitor>
240 template <typename Pred>
250 template <typename Pred>
265 template<typename HandleT, typename ElemT>
279 template<
typename BaseVecT>
286 ) : m_iterator(iterator), m_mesh(
mesh) {};
300 #include "lvr2/geometry/HalfEdgeMesh.tcc"
void circulateAroundVertex(VertexHandle vH, Visitor visitor) const
Circulates around the vertex vH, calling the visitor for each ingoing edge of the vertex.
Edge & getE(HalfEdgeHandle handle)
size_t numVertices() const final
Returns the number of vertices in the mesh.
StableVectorIterator< HalfEdgeHandle, HalfEdge > m_iterator
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.
An iterator for handles in the BaseMesh.
Handle to access half edges of the HEM.
size_t numFaces() const final
Returns the number of faces in the mesh.
OptionalEdgeHandle getOppositeEdge(FaceHandle faceH, VertexHandle vertexH) const
Get the optional edge handle of the edge lying on the vertex's opposite site.
Iterator over handles in this vector, which skips deleted elements.
OptionalHalfEdgeHandle findEdgeAroundVertex(VertexHandle vH, Pred pred) const
Iterates over all ingoing edges of one vertex, returning the first edge that satisfies the given pred...
Handle to access faces of the mesh.
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.
Index nextEdgeIndex() const
Returns the handle index which would be assigned to the next edge that is created....
void getNeighboursOfVertex(VertexHandle handle, vector< VertexHandle > &verticesOut) const final
EdgeSplitResult splitEdge(EdgeHandle edgeH)
Semantically equivalent to boost::optional<VertexHandle>
bool debugCheckMeshIntegrity() const
array< OptionalFaceHandle, 2 > getFacesOfEdge(EdgeHandle edgeH) const final
Get the two faces of an edge.
array< EdgeHandle, 3 > getEdgesOfFace(FaceHandle handle) const final
Get the three edges surrounding the given face.
void getFacesOfVertex(VertexHandle handle, vector< FaceHandle > &facesOut) const final
Index nextVertexIndex() const
Returns the handle index which would be assigned to the next vertex that is created....
Implementation of the MeshHandleIterator for the HalfEdgeMesh.
OptionalVertexHandle getOppositeVertex(FaceHandle faceH, EdgeHandle edgeH) const
Get the optional vertex handle of the vertex lying on the edge's opposite site.
MeshHandleIteratorPtr< FaceHandle > facesEnd() const final
Returns an iterator to the element following the last face of this mesh.
StableVectorIterator< HandleT, ElemT > m_iterator
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...
BaseVecT getVertexPosition(VertexHandle handle) const final
Get the position of the given vertex.
void getEdgesOfVertex(VertexHandle handle, vector< EdgeHandle > &edgesOut) const final
vector< VertexHandle > findCommonNeigbours(VertexHandle vH1, VertexHandle vH2)
Handle to access edges of the mesh.
array< VertexHandle, 2 > getVerticesOfEdge(EdgeHandle edgeH) const final
Get the two vertices of an edge.
Semantically equivalent to boost::optional<EdgeHandle>
Vertex & getV(VertexHandle handle)
MeshHandleIteratorPtr< EdgeHandle > edgesBegin() const final
Returns an iterator to the first edge of this mesh.
VertexHandle addVertex(BaseVecT pos) final
Adds a vertex with the given position to the mesh.
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.
Semantically equivalent to boost::optional<FaceHandle>
A vector which guarantees stable indices and features O(1) deletion.
Semantically equivalent to boost::optional<HalfEdgeHandle>
EdgeCollapseResult collapseEdge(EdgeHandle edgeH) final
Merges the two vertices connected by the given edge.
Handle to access vertices of the mesh.
Index nextFaceIndex() const
Returns the handle index which would be assigned to the next face that is created....
VertexSplitResult splitVertex(VertexHandle vertexToBeSplitH)
const HalfEdgeMesh< BaseVecT > & m_mesh
size_t numEdges() const final
Returns the number of edges in the mesh.
StableVector< HalfEdgeHandle, Edge > m_edges
StableVector< FaceHandle, Face > m_faces
MeshHandleIteratorPtr< FaceHandle > facesBegin() const final
Returns an iterator to the first face of this mesh.
FaceHandle addFace(VertexHandle v1H, VertexHandle v2H, VertexHandle v3H) final
Creates a face connecting the three given vertices.
OptionalHalfEdgeHandle edgeBetween(VertexHandle fromH, VertexHandle toH)
Given two vertices, find the edge pointing from one to the other.
Face & getF(FaceHandle handle)
void flipEdge(EdgeHandle edgeH) final
Performs the edge flip operation.
StableVector< VertexHandle, Vertex > m_vertices
bool containsVertex(VertexHandle vH) const
Checks if the given vertex is part of this mesh.
HemFevIterator(StableVectorIterator< HandleT, ElemT > iterator)
std::pair< BaseVecT, float > triCircumCenter(FaceHandle faceH)
pair< HalfEdgeHandle, HalfEdgeHandle > addEdgePair(VertexHandle v1H, VertexHandle v2H)
Adds a new, incomplete edge-pair.
HemEdgeIterator(StableVectorIterator< HalfEdgeHandle, HalfEdge > iterator, const HalfEdgeMesh< BaseVecT > &mesh)
std::shared_ptr< MeshBuffer > MeshBufferPtr
EdgeHandle halfToFullEdgeHandle(HalfEdgeHandle handle) const
Converts a half edge handle to a full edge handle.
Interface for triangle-meshes with adjacency information.
bool containsFace(FaceHandle fH) const
Checks if the given face is part of this mesh.
Represents a vertex in the HEM data structure.
uint32_t Index
Datatype used as index for each vertex, face and edge.
bool containsEdge(EdgeHandle eH) const
Checks if the given edge is part of this mesh.
bool isFlippable(EdgeHandle handle) const
Determines whether or not the given edge can be flipped without destroying the mesh.
A wrapper for the MeshHandleIterator to save beloved future programmers from dereferencing too much <...
void removeFace(FaceHandle handle) final
Removes the given face and all (if not connected to any other face/edge/vertex) connected edges and v...
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,...
MeshHandleIteratorPtr< VertexHandle > verticesBegin() const final
Returns an iterator to the first vertex of this mesh.
MeshHandleIteratorPtr< VertexHandle > verticesEnd() const final
Returns an iterator to the element following the last vertex of this mesh.
Half-edge data structure implementing the BaseMesh interface.
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