Public Types | Public Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
lvr2::HalfEdgeMesh< BaseVecT > Class Template Reference

Half-edge data structure implementing the BaseMesh interface. More...

#include <HalfEdgeMesh.hpp>

Inheritance diagram for lvr2::HalfEdgeMesh< BaseVecT >:
Inheritance graph
[legend]

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< EdgeHandleedgesBegin () const final
 Returns an iterator to the first edge of this mesh. More...
 
MeshHandleIteratorPtr< EdgeHandleedgesEnd () const final
 Returns an iterator to the element following the last edge of this mesh. More...
 
MeshHandleIteratorPtr< FaceHandlefacesBegin () const final
 Returns an iterator to the first face of this mesh. More...
 
MeshHandleIteratorPtr< FaceHandlefacesEnd () const final
 Returns an iterator to the element following the last face of this mesh. More...
 
vector< VertexHandlefindCommonNeigbours (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< VertexHandleverticesBegin () const final
 Returns an iterator to the first vertex of this mesh. More...
 
MeshHandleIteratorPtr< VertexHandleverticesEnd () 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< EdgeHandlegetEdgesOfVertex (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< FaceHandlegetFacesOfVertex (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< FaceHandlegetNeighboursOfFace (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< VertexHandlegetNeighboursOfVertex (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, HalfEdgeHandleaddEdgePair (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...
 
EdgegetE (HalfEdgeHandle handle)
 
const EdgegetE (HalfEdgeHandle handle) const
 
FacegetF (FaceHandle handle)
 
const FacegetF (FaceHandle handle) const
 
array< HalfEdgeHandle, 3 > getInnerEdges (FaceHandle handle) const
 Get inner edges in counter clockwise order. More...
 
VertexgetV (VertexHandle handle)
 
const VertexgetV (VertexHandle handle) const
 
EdgeHandle halfToFullEdgeHandle (HalfEdgeHandle handle) const
 Converts a half edge handle to a full edge handle. More...
 

Private Attributes

StableVector< HalfEdgeHandle, Edgem_edges
 
StableVector< FaceHandle, Facem_faces
 
StableVector< VertexHandle, Vertexm_vertices
 

Friends

template<typename >
class HemEdgeIterator
 

Detailed Description

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.

Member Typedef Documentation

◆ Edge

template<typename BaseVecT >
using lvr2::HalfEdgeMesh< BaseVecT >::Edge = HalfEdge

Definition at line 73 of file HalfEdgeMesh.hpp.

◆ Face

template<typename BaseVecT >
using lvr2::HalfEdgeMesh< BaseVecT >::Face = HalfEdgeFace

Definition at line 74 of file HalfEdgeMesh.hpp.

◆ Vertex

template<typename BaseVecT >
using lvr2::HalfEdgeMesh< BaseVecT >::Vertex = HalfEdgeVertex<BaseVecT>

Definition at line 75 of file HalfEdgeMesh.hpp.

Constructor & Destructor Documentation

◆ HalfEdgeMesh() [1/2]

template<typename BaseVecT >
lvr2::HalfEdgeMesh< BaseVecT >::HalfEdgeMesh ( )

◆ HalfEdgeMesh() [2/2]

template<typename BaseVecT >
lvr2::HalfEdgeMesh< BaseVecT >::HalfEdgeMesh ( MeshBufferPtr  ptr)

Member Function Documentation

◆ addEdgePair()

template<typename BaseVecT >
pair<HalfEdgeHandle, HalfEdgeHandle> lvr2::HalfEdgeMesh< BaseVecT >::addEdgePair ( VertexHandle  v1H,
VertexHandle  v2H 
)
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.

Returns
Both edge handles. The first edge points from v1H to v2H, the second one points from v2H to v1H.

◆ addFace()

template<typename BaseVecT >
FaceHandle lvr2::HalfEdgeMesh< BaseVecT >::addFace ( VertexHandle  v1,
VertexHandle  v2,
VertexHandle  v3 
)
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().

Returns
A handle to access the inserted face later.

Implements lvr2::BaseMesh< BaseVecT >.

◆ addVertex()

template<typename BaseVecT >
VertexHandle lvr2::HalfEdgeMesh< BaseVecT >::addVertex ( BaseVecT  pos)
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().

Returns
A handle to access the inserted vertex later.

Implements lvr2::BaseMesh< BaseVecT >.

◆ circulateAroundVertex() [1/2]

template<typename BaseVecT >
template<typename Visitor >
void lvr2::HalfEdgeMesh< BaseVecT >::circulateAroundVertex ( HalfEdgeHandle  startEdgeH,
Visitor  visitor 
) const
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.

◆ circulateAroundVertex() [2/2]

template<typename BaseVecT >
template<typename Visitor >
void lvr2::HalfEdgeMesh< BaseVecT >::circulateAroundVertex ( VertexHandle  vH,
Visitor  visitor 
) const
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.

◆ collapseEdge()

template<typename BaseVecT >
EdgeCollapseResult lvr2::HalfEdgeMesh< BaseVecT >::collapseEdge ( EdgeHandle  edgeH)
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

Returns
An EdgeCollapseResult that contains handles of the removed faces and edges and the new vertex and the new edges

Implements lvr2::BaseMesh< BaseVecT >.

◆ containsEdge()

template<typename BaseVecT >
bool lvr2::HalfEdgeMesh< BaseVecT >::containsEdge ( EdgeHandle  vH) const
virtual

Checks if the given edge is part of this mesh.

Implements lvr2::BaseMesh< BaseVecT >.

◆ containsFace()

template<typename BaseVecT >
bool lvr2::HalfEdgeMesh< BaseVecT >::containsFace ( FaceHandle  vH) const
virtual

Checks if the given face is part of this mesh.

Implements lvr2::BaseMesh< BaseVecT >.

◆ containsVertex()

template<typename BaseVecT >
bool lvr2::HalfEdgeMesh< BaseVecT >::containsVertex ( VertexHandle  vH) const
virtual

Checks if the given vertex is part of this mesh.

Implements lvr2::BaseMesh< BaseVecT >.

◆ debugCheckMeshIntegrity()

template<typename BaseVecT >
bool lvr2::HalfEdgeMesh< BaseVecT >::debugCheckMeshIntegrity ( ) const

◆ edgeBetween()

template<typename BaseVecT >
OptionalHalfEdgeHandle lvr2::HalfEdgeMesh< BaseVecT >::edgeBetween ( VertexHandle  fromH,
VertexHandle  toH 
)
private

Given two vertices, find the edge pointing from one to the other.

Returns
None, if there exists no such edge.

◆ edgesBegin()

template<typename BaseVecT >
MeshHandleIteratorPtr<EdgeHandle> lvr2::HalfEdgeMesh< BaseVecT >::edgesBegin ( ) const
finalvirtual

Returns an iterator to the first edge of this mesh.

Returns
When dereferenced, this iterator returns a handle to the current edge.

Implements lvr2::BaseMesh< BaseVecT >.

◆ edgesEnd()

template<typename BaseVecT >
MeshHandleIteratorPtr<EdgeHandle> lvr2::HalfEdgeMesh< BaseVecT >::edgesEnd ( ) const
finalvirtual

Returns an iterator to the element following the last edge of this mesh.

Implements lvr2::BaseMesh< BaseVecT >.

◆ facesBegin()

template<typename BaseVecT >
MeshHandleIteratorPtr<FaceHandle> lvr2::HalfEdgeMesh< BaseVecT >::facesBegin ( ) const
finalvirtual

Returns an iterator to the first face of this mesh.

Returns
When dereferenced, this iterator returns a handle to the current face.

Implements lvr2::BaseMesh< BaseVecT >.

◆ facesEnd()

template<typename BaseVecT >
MeshHandleIteratorPtr<FaceHandle> lvr2::HalfEdgeMesh< BaseVecT >::facesEnd ( ) const
finalvirtual

Returns an iterator to the element following the last face of this mesh.

Implements lvr2::BaseMesh< BaseVecT >.

◆ findCommonNeigbours()

template<typename BaseVecT >
vector<VertexHandle> lvr2::HalfEdgeMesh< BaseVecT >::findCommonNeigbours ( VertexHandle  vH1,
VertexHandle  vH2 
)

◆ findEdgeAroundVertex() [1/2]

template<typename BaseVecT >
template<typename Pred >
OptionalHalfEdgeHandle lvr2::HalfEdgeMesh< BaseVecT >::findEdgeAroundVertex ( HalfEdgeHandle  startEdgeH,
Pred  pred 
) const
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.

Returns
Returns None if no edge in the circle satisfies the predicate.

◆ findEdgeAroundVertex() [2/2]

template<typename BaseVecT >
template<typename Pred >
OptionalHalfEdgeHandle lvr2::HalfEdgeMesh< BaseVecT >::findEdgeAroundVertex ( VertexHandle  vH,
Pred  pred 
) const
private

Iterates over all ingoing edges of one vertex, returning the first edge that satisfies the given predicate.

Returns
Returns None if v does not have an outgoing edge or if no edge in the circle satisfies the predicate.

◆ findOrCreateEdgeBetween() [1/2]

template<typename BaseVecT >
HalfEdgeHandle lvr2::HalfEdgeMesh< BaseVecT >::findOrCreateEdgeBetween ( VertexHandle  fromH,
VertexHandle  toH 
)
private

Attempts to find an edge between the given vertices and, if none is found, creates a new edge with addEdgePair()

Returns
The half edge from fromH to toH

◆ findOrCreateEdgeBetween() [2/2]

template<typename BaseVecT >
HalfEdgeHandle lvr2::HalfEdgeMesh< BaseVecT >::findOrCreateEdgeBetween ( VertexHandle  fromH,
VertexHandle  toH,
bool &  added 
)
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.

Returns
The half edge from fromH to toH

◆ flipEdge()

template<typename BaseVecT >
void lvr2::HalfEdgeMesh< BaseVecT >::flipEdge ( EdgeHandle  edgeH)
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 >.

◆ getE() [1/2]

template<typename BaseVecT >
Edge& lvr2::HalfEdgeMesh< BaseVecT >::getE ( HalfEdgeHandle  handle)
private

◆ getE() [2/2]

template<typename BaseVecT >
const Edge& lvr2::HalfEdgeMesh< BaseVecT >::getE ( HalfEdgeHandle  handle) const
private

◆ getEdgesOfFace()

template<typename BaseVecT >
array<EdgeHandle, 3> lvr2::HalfEdgeMesh< BaseVecT >::getEdgesOfFace ( FaceHandle  handle) const
finalvirtual

Get the three edges surrounding the given face.

Returns
The edge-handles in counter-clockwise order.

Implements lvr2::BaseMesh< BaseVecT >.

◆ getEdgesOfVertex()

template<typename BaseVecT >
void lvr2::HalfEdgeMesh< BaseVecT >::getEdgesOfVertex ( VertexHandle  handle,
vector< EdgeHandle > &  edgesOut 
) const
final

◆ getF() [1/2]

template<typename BaseVecT >
Face& lvr2::HalfEdgeMesh< BaseVecT >::getF ( FaceHandle  handle)
private

◆ getF() [2/2]

template<typename BaseVecT >
const Face& lvr2::HalfEdgeMesh< BaseVecT >::getF ( FaceHandle  handle) const
private

◆ getFacesOfEdge()

template<typename BaseVecT >
array<OptionalFaceHandle, 2> lvr2::HalfEdgeMesh< BaseVecT >::getFacesOfEdge ( EdgeHandle  edgeH) const
finalvirtual

Get the two faces of an edge.

The order of the faces is not specified

Implements lvr2::BaseMesh< BaseVecT >.

◆ getFacesOfVertex()

template<typename BaseVecT >
void lvr2::HalfEdgeMesh< BaseVecT >::getFacesOfVertex ( VertexHandle  handle,
vector< FaceHandle > &  facesOut 
) const
final

◆ getInnerEdges()

template<typename BaseVecT >
array<HalfEdgeHandle, 3> lvr2::HalfEdgeMesh< BaseVecT >::getInnerEdges ( FaceHandle  handle) const
private

Get inner edges in counter clockwise order.

◆ getNeighboursOfFace()

template<typename BaseVecT >
void lvr2::HalfEdgeMesh< BaseVecT >::getNeighboursOfFace ( FaceHandle  handle,
vector< FaceHandle > &  facesOut 
) const
final

◆ getNeighboursOfVertex()

template<typename BaseVecT >
void lvr2::HalfEdgeMesh< BaseVecT >::getNeighboursOfVertex ( VertexHandle  handle,
vector< VertexHandle > &  verticesOut 
) const
final

◆ getOppositeEdge()

template<typename BaseVecT >
OptionalEdgeHandle lvr2::HalfEdgeMesh< BaseVecT >::getOppositeEdge ( FaceHandle  faceH,
VertexHandle  vertexH 
) const
virtual

Get the optional edge handle of the edge lying on the vertex's opposite site.

Parameters
faceHThe corresponding face handle
vertexHThe corresponding vertex handle
Returns
optional edge handle which lies on the faceH face on the opposite side of the vertexH vertex.

Implements lvr2::BaseMesh< BaseVecT >.

◆ getOppositeFace()

template<typename BaseVecT >
OptionalFaceHandle lvr2::HalfEdgeMesh< BaseVecT >::getOppositeFace ( FaceHandle  faceH,
VertexHandle  vertexH 
) const
virtual

Get the optional face handle of the neighboring face lying on the vertex's opposite site.

Parameters
faceHThe corresponding face handle
vertexHThe corresponding vertex handle
Returns
optional face handle of the faceH neighboring face lying on the opposite side of the vertexH vertex.

Implements lvr2::BaseMesh< BaseVecT >.

◆ getOppositeVertex()

template<typename BaseVecT >
OptionalVertexHandle lvr2::HalfEdgeMesh< BaseVecT >::getOppositeVertex ( FaceHandle  faceH,
EdgeHandle  edgeH 
) const
virtual

Get the optional vertex handle of the vertex lying on the edge's opposite site.

Parameters
faceHThe corresponding face handle
edgeHThe corresponding edge handle
Returns
optional vertex handle which lies on the faceH face on the opposite side of the edgeH edge.

Implements lvr2::BaseMesh< BaseVecT >.

◆ getV() [1/2]

template<typename BaseVecT >
Vertex& lvr2::HalfEdgeMesh< BaseVecT >::getV ( VertexHandle  handle)
private

◆ getV() [2/2]

template<typename BaseVecT >
const Vertex& lvr2::HalfEdgeMesh< BaseVecT >::getV ( VertexHandle  handle) const
private

◆ getVertexPosition() [1/2]

template<typename BaseVecT >
BaseVecT lvr2::HalfEdgeMesh< BaseVecT >::getVertexPosition ( VertexHandle  handle) const
finalvirtual

Get the position of the given vertex.

Implements lvr2::BaseMesh< BaseVecT >.

◆ getVertexPosition() [2/2]

template<typename BaseVecT >
BaseVecT& lvr2::HalfEdgeMesh< BaseVecT >::getVertexPosition ( VertexHandle  handle)
finalvirtual

Get a ref to the position of the given vertex.

Implements lvr2::BaseMesh< BaseVecT >.

◆ getVerticesOfEdge()

template<typename BaseVecT >
array<VertexHandle, 2> lvr2::HalfEdgeMesh< BaseVecT >::getVerticesOfEdge ( EdgeHandle  edgeH) const
finalvirtual

Get the two vertices of an edge.

The order of the vertices is not specified

Implements lvr2::BaseMesh< BaseVecT >.

◆ getVerticesOfFace()

template<typename BaseVecT >
array<VertexHandle, 3> lvr2::HalfEdgeMesh< BaseVecT >::getVerticesOfFace ( FaceHandle  handle) const
finalvirtual

Get the three vertices surrounding the given face.

Returns
The vertex-handles in counter-clockwise order.

Implements lvr2::BaseMesh< BaseVecT >.

◆ halfToFullEdgeHandle()

template<typename BaseVecT >
EdgeHandle lvr2::HalfEdgeMesh< BaseVecT >::halfToFullEdgeHandle ( HalfEdgeHandle  handle) const
private

Converts a half edge handle to a full edge handle.

Returns
The handle with the smaller index of the given half edge and its twin

◆ isBorderEdge()

template<typename BaseVecT >
bool lvr2::HalfEdgeMesh< BaseVecT >::isBorderEdge ( EdgeHandle  handle) const
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 >.

◆ isFlippable()

template<typename BaseVecT >
bool lvr2::HalfEdgeMesh< BaseVecT >::isFlippable ( EdgeHandle  handle) const
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 >.

◆ nextEdgeIndex()

template<typename BaseVecT >
Index lvr2::HalfEdgeMesh< BaseVecT >::nextEdgeIndex ( ) const
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 >.

◆ nextFaceIndex()

template<typename BaseVecT >
Index lvr2::HalfEdgeMesh< BaseVecT >::nextFaceIndex ( ) const
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 >.

◆ nextVertexIndex()

template<typename BaseVecT >
Index lvr2::HalfEdgeMesh< BaseVecT >::nextVertexIndex ( ) const
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 >.

◆ numEdges()

template<typename BaseVecT >
size_t lvr2::HalfEdgeMesh< BaseVecT >::numEdges ( ) const
finalvirtual

Returns the number of edges in the mesh.

Implements lvr2::BaseMesh< BaseVecT >.

◆ numFaces()

template<typename BaseVecT >
size_t lvr2::HalfEdgeMesh< BaseVecT >::numFaces ( ) const
finalvirtual

Returns the number of faces in the mesh.

Implements lvr2::BaseMesh< BaseVecT >.

◆ numVertices()

template<typename BaseVecT >
size_t lvr2::HalfEdgeMesh< BaseVecT >::numVertices ( ) const
finalvirtual

Returns the number of vertices in the mesh.

Implements lvr2::BaseMesh< BaseVecT >.

◆ removeFace()

template<typename BaseVecT >
void lvr2::HalfEdgeMesh< BaseVecT >::removeFace ( FaceHandle  handle)
finalvirtual

Removes the given face and all (if not connected to any other face/edge/vertex) connected edges and vertices.

Implements lvr2::BaseMesh< BaseVecT >.

◆ splitEdge()

template<typename BaseVecT >
EdgeSplitResult lvr2::HalfEdgeMesh< BaseVecT >::splitEdge ( EdgeHandle  edgeH)

◆ splitVertex() [1/2]

template<typename BaseVecT >
void lvr2::HalfEdgeMesh< BaseVecT >::splitVertex ( EdgeHandle  eH,
VertexHandle  vH,
BaseVecT  pos1,
BaseVecT  pos2 
)

◆ splitVertex() [2/2]

template<typename BaseVecT >
VertexSplitResult lvr2::HalfEdgeMesh< BaseVecT >::splitVertex ( VertexHandle  vertexToBeSplitH)

◆ triCircumCenter()

template<typename BaseVecT >
std::pair<BaseVecT, float> lvr2::HalfEdgeMesh< BaseVecT >::triCircumCenter ( FaceHandle  faceH)

◆ verticesBegin()

template<typename BaseVecT >
MeshHandleIteratorPtr<VertexHandle> lvr2::HalfEdgeMesh< BaseVecT >::verticesBegin ( ) const
finalvirtual

Returns an iterator to the first vertex of this mesh.

Returns
When dereferenced, this iterator returns a handle to the current vertex.

Implements lvr2::BaseMesh< BaseVecT >.

◆ verticesEnd()

template<typename BaseVecT >
MeshHandleIteratorPtr<VertexHandle> lvr2::HalfEdgeMesh< BaseVecT >::verticesEnd ( ) const
finalvirtual

Returns an iterator to the element following the last vertex of this mesh.

Implements lvr2::BaseMesh< BaseVecT >.

Friends And Related Function Documentation

◆ HemEdgeIterator

template<typename BaseVecT >
template<typename >
friend class HemEdgeIterator
friend

Definition at line 261 of file HalfEdgeMesh.hpp.

Member Data Documentation

◆ m_edges

template<typename BaseVecT >
StableVector<HalfEdgeHandle, Edge> lvr2::HalfEdgeMesh< BaseVecT >::m_edges
private

Definition at line 149 of file HalfEdgeMesh.hpp.

◆ m_faces

template<typename BaseVecT >
StableVector<FaceHandle, Face> lvr2::HalfEdgeMesh< BaseVecT >::m_faces
private

Definition at line 150 of file HalfEdgeMesh.hpp.

◆ m_vertices

template<typename BaseVecT >
StableVector<VertexHandle, Vertex> lvr2::HalfEdgeMesh< BaseVecT >::m_vertices
private

Definition at line 151 of file HalfEdgeMesh.hpp.


The documentation for this class was generated from the following file:


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:27