|
FaceHandle | addFace (VertexHandle v1H, VertexHandle v2H, VertexHandle v3H) final |
| Creates a face connecting the three given vertices. More...
|
|
VertexHandle | addVertex (BaseVecT pos) final |
| Adds a vertex with the given position to the mesh. More...
|
|
EdgeCollapseResult | collapseEdge (EdgeHandle edgeH) final |
| Merges the two vertices connected by the given edge. More...
|
|
bool | containsEdge (EdgeHandle eH) const |
| Checks if the given edge is part of this mesh. More...
|
|
bool | containsFace (FaceHandle fH) const |
| Checks if the given face is part of this mesh. More...
|
|
bool | containsVertex (VertexHandle vH) const |
| Checks if the given vertex is part of this mesh. More...
|
|
bool | debugCheckMeshIntegrity () const |
|
MeshHandleIteratorPtr< EdgeHandle > | edgesBegin () const final |
| Returns an iterator to the first edge of this mesh. More...
|
|
MeshHandleIteratorPtr< EdgeHandle > | edgesEnd () const final |
| Returns an iterator to the element following the last edge of this mesh. More...
|
|
MeshHandleIteratorPtr< FaceHandle > | facesBegin () const final |
| Returns an iterator to the first face of this mesh. More...
|
|
MeshHandleIteratorPtr< FaceHandle > | facesEnd () const final |
| Returns an iterator to the element following the last face of this mesh. More...
|
|
vector< VertexHandle > | findCommonNeigbours (VertexHandle vH1, VertexHandle vH2) |
|
void | flipEdge (EdgeHandle edgeH) final |
| Performs the edge flip operation. More...
|
|
array< EdgeHandle, 3 > | getEdgesOfFace (FaceHandle handle) const final |
| Get the three edges surrounding the given face. More...
|
|
void | getEdgesOfVertex (VertexHandle handle, vector< EdgeHandle > &edgesOut) const final |
|
array< OptionalFaceHandle, 2 > | getFacesOfEdge (EdgeHandle edgeH) const final |
| Get the two faces of an edge. More...
|
|
void | getFacesOfVertex (VertexHandle handle, vector< FaceHandle > &facesOut) const final |
|
void | getNeighboursOfFace (FaceHandle handle, vector< FaceHandle > &facesOut) const final |
|
void | getNeighboursOfVertex (VertexHandle handle, vector< VertexHandle > &verticesOut) const final |
|
OptionalEdgeHandle | getOppositeEdge (FaceHandle faceH, VertexHandle vertexH) const |
| Get the optional edge handle of the edge lying on the vertex's opposite site. More...
|
|
OptionalFaceHandle | getOppositeFace (FaceHandle faceH, VertexHandle vertexH) const |
| Get the optional face handle of the neighboring face lying on the vertex's opposite site. More...
|
|
OptionalVertexHandle | getOppositeVertex (FaceHandle faceH, EdgeHandle edgeH) const |
| Get the optional vertex handle of the vertex lying on the edge's opposite site. More...
|
|
BaseVecT | getVertexPosition (VertexHandle handle) const final |
| Get the position of the given vertex. More...
|
|
BaseVecT & | getVertexPosition (VertexHandle handle) final |
| Get a ref to the position of the given vertex. More...
|
|
array< VertexHandle, 2 > | getVerticesOfEdge (EdgeHandle edgeH) const final |
| Get the two vertices of an edge. More...
|
|
array< VertexHandle, 3 > | getVerticesOfFace (FaceHandle handle) const final |
| Get the three vertices surrounding the given face. More...
|
|
| HalfEdgeMesh () |
|
| HalfEdgeMesh (MeshBufferPtr ptr) |
|
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. More...
|
|
bool | isFlippable (EdgeHandle handle) const |
| Determines whether or not the given edge can be flipped without destroying the mesh. More...
|
|
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. More...
|
|
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. More...
|
|
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. More...
|
|
size_t | numEdges () const final |
| Returns the number of edges in the mesh. More...
|
|
size_t | numFaces () const final |
| Returns the number of faces in the mesh. More...
|
|
size_t | numVertices () const final |
| Returns the number of vertices in the mesh. More...
|
|
void | removeFace (FaceHandle handle) final |
| Removes the given face and all (if not connected to any other face/edge/vertex) connected edges and vertices. More...
|
|
EdgeSplitResult | splitEdge (EdgeHandle edgeH) |
|
VertexSplitResult | splitVertex (VertexHandle vertexToBeSplitH) |
|
void | splitVertex (EdgeHandle eH, VertexHandle vH, BaseVecT pos1, BaseVecT pos2) |
|
std::pair< BaseVecT, float > | triCircumCenter (FaceHandle faceH) |
|
MeshHandleIteratorPtr< VertexHandle > | verticesBegin () const final |
| Returns an iterator to the first vertex of this mesh. More...
|
|
MeshHandleIteratorPtr< VertexHandle > | verticesEnd () const final |
| Returns an iterator to the element following the last vertex of this mesh. More...
|
|
BaseVecT::CoordType | calcFaceArea (FaceHandle handle) const |
| Calc and return the area of the requested face. More...
|
|
BaseVecT | calcFaceCentroid (FaceHandle handle) const |
| Calc and return the centroid of the requested face. More...
|
|
virtual EdgeIteratorProxy< BaseVecT > | edges () const |
| Method for usage in range-based for-loops. More...
|
|
virtual FaceIteratorProxy< BaseVecT > | faces () const |
| Method for usage in range-based for-loops. More...
|
|
virtual OptionalEdgeHandle | getEdgeBetween (VertexHandle aH, VertexHandle bH) const |
| If the two given vertices are connected by an edge, it is returned. None otherwise. More...
|
|
virtual void | getEdgesOfVertex (VertexHandle handle, std::vector< EdgeHandle > &edgesOut) const =0 |
| Get a list of edges around the given vertex. More...
|
|
virtual std::vector< EdgeHandle > | getEdgesOfVertex (VertexHandle handle) const |
| Get a list of edges around the given vertex. More...
|
|
virtual OptionalFaceHandle | getFaceBetween (VertexHandle aH, VertexHandle bH, VertexHandle cH) const |
| If all vertices are part of one face, this face is returned. None otherwise. More...
|
|
virtual void | getFacesOfVertex (VertexHandle handle, std::vector< FaceHandle > &facesOut) const =0 |
| Get a list of faces the given vertex belongs to. More...
|
|
virtual std::vector< FaceHandle > | getFacesOfVertex (VertexHandle handle) const |
| Get a list of faces the given vertex belongs to. More...
|
|
virtual void | getNeighboursOfFace (FaceHandle handle, std::vector< FaceHandle > &facesOut) const =0 |
| Get face handles of the neighbours of the requested face. More...
|
|
virtual std::vector< FaceHandle > | getNeighboursOfFace (FaceHandle handle) const |
| Get face handles of the neighbours of the requested face. More...
|
|
virtual void | getNeighboursOfVertex (VertexHandle handle, std::vector< VertexHandle > &verticesOut) const =0 |
| Get vertex handles of the neighbours of the requested vertex. More...
|
|
virtual std::vector< VertexHandle > | getNeighboursOfVertex (VertexHandle handle) const |
| Get a list of vertices around the given vertex. More...
|
|
virtual OptionalVertexHandle | getVertexBetween (EdgeHandle aH, EdgeHandle bH) const |
| If the given edges share a vertex, it is returned. None otherwise. More...
|
|
virtual std::array< BaseVecT, 3 > | getVertexPositionsOfFace (FaceHandle handle) const |
| Get the points of the requested face. More...
|
|
virtual bool | isCollapsable (EdgeHandle handle) const |
| Determines whether or not an edge collapse of the given edge is possible without creating invalid meshes. More...
|
|
virtual bool | isFaceInsertionValid (VertexHandle v1, VertexHandle v2, VertexHandle v3) const |
| Check whether or not inserting a face between the given vertices would be valid. More...
|
|
virtual uint8_t | numAdjacentFaces (EdgeHandle handle) const |
| Returns the number of adjacent faces to the given edge. More...
|
|
virtual VertexIteratorProxy< BaseVecT > | vertices () const |
| Method for usage in range-based for-loops. More...
|
|
virtual | ~BaseMesh () |
|
|
pair< HalfEdgeHandle, HalfEdgeHandle > | addEdgePair (VertexHandle v1H, VertexHandle v2H) |
| Adds a new, incomplete edge-pair. More...
|
|
template<typename Visitor > |
void | circulateAroundVertex (VertexHandle vH, Visitor visitor) const |
| Circulates around the vertex vH , calling the visitor for each ingoing edge of the vertex. More...
|
|
template<typename Visitor > |
void | circulateAroundVertex (HalfEdgeHandle startEdgeH, Visitor visitor) const |
| Circulates around the vertex startEdgeH.target , calling the visitor for each ingoing edge of the vertex. More...
|
|
OptionalHalfEdgeHandle | edgeBetween (VertexHandle fromH, VertexHandle toH) |
| Given two vertices, find the edge pointing from one to the other. More...
|
|
template<typename Pred > |
OptionalHalfEdgeHandle | findEdgeAroundVertex (VertexHandle vH, Pred pred) const |
| Iterates over all ingoing edges of one vertex, returning the first edge that satisfies the given predicate. More...
|
|
template<typename Pred > |
OptionalHalfEdgeHandle | findEdgeAroundVertex (HalfEdgeHandle startEdgeH, Pred pred) const |
| Iterates over all ingoing edges of the vertex startEdge.target , starting at the edge startEdgeH , returning the first edge that satisfies the given predicate. More...
|
|
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 addEdgePair() More...
|
|
HalfEdgeHandle | findOrCreateEdgeBetween (VertexHandle fromH, VertexHandle toH, bool &added) |
| Attempts to find an edge between the given vertices and, if none is found, creates a new edge with addEdgePair() and sets the add boolean to true. More...
|
|
Edge & | getE (HalfEdgeHandle handle) |
|
const Edge & | getE (HalfEdgeHandle handle) const |
|
Face & | getF (FaceHandle handle) |
|
const Face & | getF (FaceHandle handle) const |
|
array< HalfEdgeHandle, 3 > | getInnerEdges (FaceHandle handle) const |
| Get inner edges in counter clockwise order. More...
|
|
Vertex & | getV (VertexHandle handle) |
|
const Vertex & | getV (VertexHandle handle) const |
|
EdgeHandle | halfToFullEdgeHandle (HalfEdgeHandle handle) const |
| Converts a half edge handle to a full edge handle. More...
|
|
template<typename BaseVecT>
class lvr2::HalfEdgeMesh< BaseVecT >
Half-edge data structure implementing the BaseMesh
interface.
This implementation uses a half-edge structure. This encodes many connectivity details explicitly, enabling fast lookup. However, HEMs are primarily intended for non-triangle meshes (variable number of edges per face). Using it for triangle meshes might be overkill and results in a memory overhead.
Definition at line 70 of file HalfEdgeMesh.hpp.