Half-edge data structure implementing the BaseMesh
interface.
More...
#include <HalfEdgeMesh.hpp>
Public Types | |
using | Edge = HalfEdge |
using | Face = HalfEdgeFace |
using | Vertex = HalfEdgeVertex< BaseVecT > |
Public Member Functions | |
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) |
void | splitVertex (EdgeHandle eH, VertexHandle vH, BaseVecT pos1, BaseVecT pos2) |
VertexSplitResult | splitVertex (VertexHandle vertexToBeSplitH) |
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... | |
Public Member Functions inherited from lvr2::BaseMesh< BaseVecT > | |
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 std::vector< EdgeHandle > | getEdgesOfVertex (VertexHandle handle) const |
Get a list of edges around the given vertex. More... | |
virtual void | getEdgesOfVertex (VertexHandle handle, std::vector< EdgeHandle > &edgesOut) const =0 |
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 std::vector< FaceHandle > | getFacesOfVertex (VertexHandle handle) const |
Get a list of faces the given vertex belongs to. 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 > | getNeighboursOfFace (FaceHandle handle) const |
Get face handles of the neighbours of the requested face. 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< VertexHandle > | getNeighboursOfVertex (VertexHandle handle) const |
Get a list of vertices around the given vertex. More... | |
virtual void | getNeighboursOfVertex (VertexHandle handle, std::vector< VertexHandle > &verticesOut) const =0 |
Get vertex handles of the neighbours of the requested 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 () |
Private Member Functions | |
pair< HalfEdgeHandle, HalfEdgeHandle > | addEdgePair (VertexHandle v1H, VertexHandle v2H) |
Adds a new, incomplete edge-pair. 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... | |
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... | |
OptionalHalfEdgeHandle | edgeBetween (VertexHandle fromH, VertexHandle toH) |
Given two vertices, find the edge pointing from one to the other. 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... | |
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... | |
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... | |
Private Attributes | |
StableVector< HalfEdgeHandle, Edge > | m_edges |
StableVector< FaceHandle, Face > | m_faces |
StableVector< VertexHandle, Vertex > | m_vertices |
Friends | |
template<typename > | |
class | HemEdgeIterator |
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.
using lvr2::HalfEdgeMesh< BaseVecT >::Edge = HalfEdge |
Definition at line 73 of file HalfEdgeMesh.hpp.
using lvr2::HalfEdgeMesh< BaseVecT >::Face = HalfEdgeFace |
Definition at line 74 of file HalfEdgeMesh.hpp.
using lvr2::HalfEdgeMesh< BaseVecT >::Vertex = HalfEdgeVertex<BaseVecT> |
Definition at line 75 of file HalfEdgeMesh.hpp.
lvr2::HalfEdgeMesh< BaseVecT >::HalfEdgeMesh | ( | ) |
lvr2::HalfEdgeMesh< BaseVecT >::HalfEdgeMesh | ( | MeshBufferPtr | ptr | ) |
|
private |
Adds a new, incomplete edge-pair.
This method is private and unsafe, because it leaves some fields uninitialized. The invariants of this mesh are broken after calling this method and the caller has to fix those broken invariants.
In particular, no next
handle is set or changed. The outgoing
handle of the vertices is not changed (or set) either.
|
finalvirtual |
Creates a face connecting the three given vertices.
Important: The face's vertices have to be given in front-face counter- clockwise order. This means that, when looking at the face's front, the vertices would appear in counter-clockwise order. Or in more mathy terms: the face's normal is equal to (v1 - v2) x (v1 - v3) in the right-handed coordinate system (where x
is cross-product).
This method panics if an insertion is not possible. You can check whether or not an insertion is valid by using isFaceInsertionValid()
.
Implements lvr2::BaseMesh< BaseVecT >.
|
finalvirtual |
Adds a vertex with the given position to the mesh.
The vertex is not connected to anything after calling this method. To add this vertex to a face, use addFace()
.
Implements lvr2::BaseMesh< BaseVecT >.
|
private |
Circulates around the vertex startEdgeH.target
, calling the visitor
for each ingoing edge of the vertex.
This works exactly as the other overload, but specifically starts at the edge startEdgeH
instead of vH.outgoing.twin
.
|
private |
Circulates around the vertex vH
, calling the visitor
for each ingoing edge of the vertex.
The edges are visited in clockwise order. The iteration stops if all edges were visited once or if the visitor returns false
. It has to return true
to keep circulating. If the vertex has no outgoing edge, this method does nothing.
|
finalvirtual |
Merges the two vertices connected by the given edge.
If existing, the two neighboring faces or triangles without faces and their edges are removed and replaced by two new edges The vertices at the start and end of the given edge are removed and replaced by a new vertex at the center of the previous vertex positions
Implements lvr2::BaseMesh< BaseVecT >.
|
virtual |
Checks if the given edge is part of this mesh.
Implements lvr2::BaseMesh< BaseVecT >.
|
virtual |
Checks if the given face is part of this mesh.
Implements lvr2::BaseMesh< BaseVecT >.
|
virtual |
Checks if the given vertex is part of this mesh.
Implements lvr2::BaseMesh< BaseVecT >.
bool lvr2::HalfEdgeMesh< BaseVecT >::debugCheckMeshIntegrity | ( | ) | const |
|
private |
Given two vertices, find the edge pointing from one to the other.
|
finalvirtual |
Returns an iterator to the first edge of this mesh.
Implements lvr2::BaseMesh< BaseVecT >.
|
finalvirtual |
Returns an iterator to the element following the last edge of this mesh.
Implements lvr2::BaseMesh< BaseVecT >.
|
finalvirtual |
Returns an iterator to the first face of this mesh.
Implements lvr2::BaseMesh< BaseVecT >.
|
finalvirtual |
Returns an iterator to the element following the last face of this mesh.
Implements lvr2::BaseMesh< BaseVecT >.
vector<VertexHandle> lvr2::HalfEdgeMesh< BaseVecT >::findCommonNeigbours | ( | VertexHandle | vH1, |
VertexHandle | vH2 | ||
) |
|
private |
Iterates over all ingoing edges of the vertex startEdge.target
, starting at the edge startEdgeH
, returning the first edge that satisfies the given predicate.
|
private |
Iterates over all ingoing edges of one vertex, returning the first edge that satisfies the given predicate.
v
does not have an outgoing edge or if no edge in the circle satisfies the predicate.
|
private |
Attempts to find an edge between the given vertices and, if none is found, creates a new edge with addEdgePair()
fromH
to toH
|
private |
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.
fromH
to toH
|
finalvirtual |
Performs the edge flip operation.
This operation turns an edge and the two adjacent faces within a four vertex region by 90°. The edge is now connected to two new vertices; the new edge would cross the old one.
Important: the given edge needs to be flippable. You can check that property with isFlippable()
. If that property is not satisfied, this method will panic.
Note that while this method modifies connectivity information, it does not add or remove any elements. This implies that it doesn't invalidate any handles.
The user of this method has to pay attention to what edges to flip. It's easily possible to create unrealistic meshes with this method (things like zero volume and stuff like that). However, it doesn't destroy the mesh in itself or create non-manifold meshes.
Implements lvr2::BaseMesh< BaseVecT >.
|
private |
|
private |
|
finalvirtual |
Get the three edges surrounding the given face.
Implements lvr2::BaseMesh< BaseVecT >.
|
final |
|
private |
|
private |
|
finalvirtual |
Get the two faces of an edge.
The order of the faces is not specified
Implements lvr2::BaseMesh< BaseVecT >.
|
final |
|
private |
Get inner edges in counter clockwise order.
|
final |
|
final |
|
virtual |
Get the optional edge handle of the edge lying on the vertex's opposite site.
faceH | The corresponding face handle |
vertexH | The corresponding vertex handle |
faceH
face on the opposite side of the vertexH
vertex. Implements lvr2::BaseMesh< BaseVecT >.
|
virtual |
Get the optional face handle of the neighboring face lying on the vertex's opposite site.
faceH | The corresponding face handle |
vertexH | The corresponding vertex handle |
faceH
neighboring face lying on the opposite side of the vertexH
vertex. Implements lvr2::BaseMesh< BaseVecT >.
|
virtual |
Get the optional vertex handle of the vertex lying on the edge's opposite site.
faceH | The corresponding face handle |
edgeH | The corresponding edge handle |
faceH
face on the opposite side of the edgeH
edge. Implements lvr2::BaseMesh< BaseVecT >.
|
private |
|
private |
|
finalvirtual |
Get the position of the given vertex.
Implements lvr2::BaseMesh< BaseVecT >.
|
finalvirtual |
Get a ref to the position of the given vertex.
Implements lvr2::BaseMesh< BaseVecT >.
|
finalvirtual |
Get the two vertices of an edge.
The order of the vertices is not specified
Implements lvr2::BaseMesh< BaseVecT >.
|
finalvirtual |
Get the three vertices surrounding the given face.
Implements lvr2::BaseMesh< BaseVecT >.
|
private |
Converts a half edge handle to a full edge handle.
|
virtual |
Determines wheter the given edge is an border edge, i.e., if it is connected to two faces or not.
Implements lvr2::BaseMesh< BaseVecT >.
|
virtual |
Determines whether or not the given edge can be flipped without destroying the mesh.
The mesh could be destroyed by invalidating mesh connectivity information or by making it non-manifold.
Reimplemented from lvr2::BaseMesh< BaseVecT >.
|
virtual |
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.
Implements lvr2::BaseMesh< BaseVecT >.
|
virtual |
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.
Implements lvr2::BaseMesh< BaseVecT >.
|
virtual |
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.
Implements lvr2::BaseMesh< BaseVecT >.
|
finalvirtual |
Returns the number of edges in the mesh.
Implements lvr2::BaseMesh< BaseVecT >.
|
finalvirtual |
Returns the number of faces in the mesh.
Implements lvr2::BaseMesh< BaseVecT >.
|
finalvirtual |
Returns the number of vertices in the mesh.
Implements lvr2::BaseMesh< BaseVecT >.
|
finalvirtual |
Removes the given face and all (if not connected to any other face/edge/vertex) connected edges and vertices.
Implements lvr2::BaseMesh< BaseVecT >.
EdgeSplitResult lvr2::HalfEdgeMesh< BaseVecT >::splitEdge | ( | EdgeHandle | edgeH | ) |
void lvr2::HalfEdgeMesh< BaseVecT >::splitVertex | ( | EdgeHandle | eH, |
VertexHandle | vH, | ||
BaseVecT | pos1, | ||
BaseVecT | pos2 | ||
) |
VertexSplitResult lvr2::HalfEdgeMesh< BaseVecT >::splitVertex | ( | VertexHandle | vertexToBeSplitH | ) |
std::pair<BaseVecT, float> lvr2::HalfEdgeMesh< BaseVecT >::triCircumCenter | ( | FaceHandle | faceH | ) |
|
finalvirtual |
Returns an iterator to the first vertex of this mesh.
Implements lvr2::BaseMesh< BaseVecT >.
|
finalvirtual |
Returns an iterator to the element following the last vertex of this mesh.
Implements lvr2::BaseMesh< BaseVecT >.
Definition at line 261 of file HalfEdgeMesh.hpp.
|
private |
Definition at line 149 of file HalfEdgeMesh.hpp.
|
private |
Definition at line 150 of file HalfEdgeMesh.hpp.
|
private |
Definition at line 151 of file HalfEdgeMesh.hpp.