Interface for triangle-meshes with adjacency information. More...
#include <BaseMesh.hpp>
Public Member Functions | |
virtual FaceHandle | addFace (VertexHandle v1, VertexHandle v2, VertexHandle v3)=0 |
Creates a face connecting the three given vertices. More... | |
virtual VertexHandle | addVertex (BaseVecT pos)=0 |
Adds a vertex with the given position to the 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 EdgeCollapseResult | collapseEdge (EdgeHandle edgeH)=0 |
Merges the two vertices connected by the given edge. More... | |
virtual bool | containsEdge (EdgeHandle vH) const =0 |
Checks if the given edge is part of this mesh. More... | |
virtual bool | containsFace (FaceHandle vH) const =0 |
Checks if the given face is part of this mesh. More... | |
virtual bool | containsVertex (VertexHandle vH) const =0 |
Checks if the given vertex is part of this mesh. More... | |
virtual EdgeIteratorProxy< BaseVecT > | edges () const |
Method for usage in range-based for-loops. More... | |
virtual MeshHandleIteratorPtr< EdgeHandle > | edgesBegin () const =0 |
Returns an iterator to the first edge of this mesh. More... | |
virtual MeshHandleIteratorPtr< EdgeHandle > | edgesEnd () const =0 |
Returns an iterator to the element following the last edge of this mesh. More... | |
virtual FaceIteratorProxy< BaseVecT > | faces () const |
Method for usage in range-based for-loops. More... | |
virtual MeshHandleIteratorPtr< FaceHandle > | facesBegin () const =0 |
Returns an iterator to the first face of this mesh. More... | |
virtual MeshHandleIteratorPtr< FaceHandle > | facesEnd () const =0 |
Returns an iterator to the element following the last face of this mesh. More... | |
virtual void | flipEdge (EdgeHandle edgeH)=0 |
Performs the edge flip operation. 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::array< EdgeHandle, 3 > | getEdgesOfFace (FaceHandle handle) const =0 |
Get the three edges surrounding the given face. 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::array< OptionalFaceHandle, 2 > | getFacesOfEdge (EdgeHandle edgeH) const =0 |
Get the two faces of an edge. 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 OptionalEdgeHandle | getOppositeEdge (FaceHandle faceH, VertexHandle vertexH) const =0 |
Get the optional edge handle of the edge lying on the vertex's opposite site. More... | |
virtual OptionalFaceHandle | getOppositeFace (FaceHandle faceH, VertexHandle vertexH) const =0 |
Get the optional face handle of the neighboring face lying on the vertex's opposite site. More... | |
virtual OptionalVertexHandle | getOppositeVertex (FaceHandle faceH, EdgeHandle edgeH) const =0 |
Get the optional vertex handle of the vertex lying on the edge's opposite site. More... | |
virtual OptionalVertexHandle | getVertexBetween (EdgeHandle aH, EdgeHandle bH) const |
If the given edges share a vertex, it is returned. None otherwise. More... | |
virtual BaseVecT | getVertexPosition (VertexHandle handle) const =0 |
Get the position of the given vertex. More... | |
virtual BaseVecT & | getVertexPosition (VertexHandle handle)=0 |
Get a ref to the position of the given vertex. More... | |
virtual std::array< BaseVecT, 3 > | getVertexPositionsOfFace (FaceHandle handle) const |
Get the points of the requested face. More... | |
virtual std::array< VertexHandle, 2 > | getVerticesOfEdge (EdgeHandle edgeH) const =0 |
Get the two vertices of an edge. More... | |
virtual std::array< VertexHandle, 3 > | getVerticesOfFace (FaceHandle handle) const =0 |
Get the three vertices surrounding the given face. More... | |
virtual bool | isBorderEdge (EdgeHandle handle) const =0 |
Determines wheter the given edge is an border edge, i.e., if it is connected to two faces or not. 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 bool | isFlippable (EdgeHandle handle) const |
Determines whether or not the given edge can be flipped without destroying the mesh. More... | |
virtual Index | nextEdgeIndex () const =0 |
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... | |
virtual Index | nextFaceIndex () const =0 |
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... | |
virtual Index | nextVertexIndex () const =0 |
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... | |
virtual uint8_t | numAdjacentFaces (EdgeHandle handle) const |
Returns the number of adjacent faces to the given edge. More... | |
virtual size_t | numEdges () const =0 |
Returns the number of edges in the mesh. More... | |
virtual size_t | numFaces () const =0 |
Returns the number of faces in the mesh. More... | |
virtual size_t | numVertices () const =0 |
Returns the number of vertices in the mesh. More... | |
virtual void | removeFace (FaceHandle handle)=0 |
Removes the given face and all (if not connected to any other face/edge/vertex) connected edges and vertices. More... | |
virtual VertexIteratorProxy< BaseVecT > | vertices () const |
Method for usage in range-based for-loops. More... | |
virtual MeshHandleIteratorPtr< VertexHandle > | verticesBegin () const =0 |
Returns an iterator to the first vertex of this mesh. More... | |
virtual MeshHandleIteratorPtr< VertexHandle > | verticesEnd () const =0 |
Returns an iterator to the element following the last vertex of this mesh. More... | |
virtual | ~BaseMesh () |
Interface for triangle-meshes with adjacency information.
This interface represents meshes that contain information about the conectivity of their faces, edges and vertices. They make it possible to access adjacent faces/edges/vertices in constant time.
Faces, edges and vertices in these meshes are explicitly represented (the phrase "faces, edge or vertex" is often abbreviated "FEV"). To talk about one specific FEV, so called handles are used. A handle is basically an index which is used to identify a FEV. Note that the internal structures used to represent FEVs are not exposed in this interface. This means you'll never write something like vertex.outgoingEdge
, but you'll always use methods of this interface to get information about a FEV.
Meshes are mainly used to store connectivity information. They are not used to store arbitrary data for each FEV. To do that, you should use FEV maps which allow you to associate arbitrary data with a FEV (and more). For more information about that, please refer to the documentation in VectorMap
. There is one important exception, though: the 3D position of vertices is stored inside the mesh directly. This is actually rather inconsistent with the whole design, but positions are used a lot – so it is convenient to store them in the mesh. But this might change in the future.
This interface cannot be used for arbitrarily connected meshes. Instead, only manifold meshes can be represented. In particular, this means that each connected component of the mesh has to be a planar graph (you could draw it on a piece of paper without edges crossing). As a consequence we can use terms like "clockwise" and "counter-clockwise" (a property that I think is called "orientable"). When doing that, we assume a planar embedding that shows the face's normals sticking "out of the paper". In easier terms: draw the graph (represented by the mesh) on a paper and draw it in the way such that you can see the front of all faces. When we talk about "clockwise" and "counter-clockwise" we are talking about this embedding – when looking at the face.
Definition at line 140 of file BaseMesh.hpp.
|
inlinevirtual |
Definition at line 144 of file BaseMesh.hpp.
|
pure virtual |
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()
.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
pure virtual |
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()
.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
BaseVecT::CoordType lvr2::BaseMesh< BaseVecT >::calcFaceArea | ( | FaceHandle | handle | ) | const |
Calc and return the area of the requested face.
BaseVecT lvr2::BaseMesh< BaseVecT >::calcFaceCentroid | ( | FaceHandle | handle | ) | const |
Calc and return the centroid of the requested face.
|
pure virtual |
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
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
pure virtual |
Checks if the given edge is part of this mesh.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
pure virtual |
Checks if the given face is part of this mesh.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
pure virtual |
Checks if the given vertex is part of this mesh.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
virtual |
Method for usage in range-based for-loops.
Returns a simple proxy object that uses edgesBegin()
and edgesEnd()
.
|
pure virtual |
Returns an iterator to the first edge of this mesh.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
pure virtual |
Returns an iterator to the element following the last edge of this mesh.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
virtual |
Method for usage in range-based for-loops.
Returns a simple proxy object that uses facesBegin()
and facesEnd()
.
|
pure virtual |
Returns an iterator to the first face of this mesh.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
pure virtual |
Returns an iterator to the element following the last face of this mesh.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
pure virtual |
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.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
virtual |
If the two given vertices are connected by an edge, it is returned. None otherwise.
|
pure virtual |
Get the three edges surrounding the given face.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
virtual |
Get a list of edges around the given vertex.
This method is implemented using the pure virtual method getEdgesOfVertex(VertexHandle, vector<EdgeHandle>&)
. If you are calling this method in a loop, you should probably call the more manual method (with the out vector) to avoid useless heap allocations.
|
pure virtual |
Get a list of edges around the given vertex.
The face handles are written into the edgesOut
vector. This is done to reduce the number of heap allocations if this method is called in a loop. If you are not calling it in a loop or can't, for some reason, take advantages of this method's signature, you can call the other overload of this method which just returns the vector. Such convenient.
Note: you probably should remember to clear()
the vector before passing it into this method.
edgesOut | The handles of the edges around handle will be written into this vector in clockwise order. |
|
virtual |
If all vertices are part of one face, this face is returned. None otherwise.
The vertices don't have to be in a specific order. In particular, this method will find a face regardless of whether the vertices are given in clockwise or counter-clockwise order.
|
pure virtual |
Get the two faces of an edge.
The order of the faces is not specified
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
virtual |
Get a list of faces the given vertex belongs to.
This method is implemented using the pure virtual method getFacesOfVertex(VertexHandle, vector<FaceHandle>&)
. If you are calling this method in a loop, you should probably call the more manual method (with the out vector) to avoid useless heap allocations.
|
pure virtual |
Get a list of faces the given vertex belongs to.
The face handles are written into the facesOut
vector. This is done to reduce the number of heap allocations if this method is called in a loop. If you are not calling it in a loop or can't, for some reason, take advantages of this method's signature, you can call the other overload of this method which just returns the vector. Such convinient.
Note: you probably should remember to clear()
the vector before passing it into this method.
facesOut | The handles of the faces around handle will be written into this vector in clockwise order. |
|
virtual |
Get face handles of the neighbours of the requested face.
This method is implemented using the pure virtual method getNeighboursOfFace(FaceHandle, vector<FaceHandle>&)
. If you are calling this method in a loop, you should probably call the more manual method (with the out vector) to avoid useless heap allocations.
|
pure virtual |
Get face handles of the neighbours of the requested face.
The face handles are written into the facesOut
vector. This is done to reduce the number of heap allocations if this method is called in a loop. If you are not calling it in a loop or can't, for some reason, take advantages of this method's signature, you can call the other overload of this method which just returns the vector. Such convinient.
Note: you probably should remember to clear()
the vector before passing it into this method.
facesOut | The face-handles of the neighbours of handle will be written into this vector in counter-clockwise order. There are at most three neighbours of a face, so this method will push 0, 1, 2 or 3 handles to facesOut . |
|
virtual |
Get a list of vertices around the given vertex.
This method is implemented using the pure virtual method getNeighboursOfVertex(VertexHandle, vector<EdgeHandle>&)
. If you are calling this method in a loop, you should probably call the more manual method (with the out vector) to avoid useless heap allocations.
|
pure virtual |
Get vertex handles of the neighbours of the requested vertex.
The vertex handles are written into the verticesOut
vector. This is done to reduce the number of heap allocations if this method is called in a loop. If you are not calling it in a loop or can't, for some reason, take advantages of this method's signature, you can call the other overload of this method which just returns the vector. Such convenient.
Note: you probably should remember to clear()
the vector before passing it into this method.
verticesOut | The vertex-handles of the neighbours of handle will be written into this vector in clockwise order. |
|
pure 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. Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
pure 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. Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
pure 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. Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
virtual |
If the given edges share a vertex, it is returned. None otherwise.
|
pure virtual |
Get the position of the given vertex.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
pure virtual |
Get a ref to the position of the given vertex.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
virtual |
Get the points of the requested face.
|
pure virtual |
Get the two vertices of an edge.
The order of the vertices is not specified
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
pure virtual |
Get the three vertices surrounding the given face.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
pure virtual |
Determines wheter the given edge is an border edge, i.e., if it is connected to two faces or not.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
virtual |
Determines whether or not an edge collapse of the given edge is possible without creating invalid meshes.
For example, an edge collapse can create non-manifold meshes in some situations. Thus, those collapses are not allowed and collapseEdge()
will panic if called with a non-collapsable edge.
|
virtual |
Check whether or not inserting a face between the given vertices would be valid.
Adding a face is invalid if it destroys the mesh in any kind, like making it non-manifold, non-orientable or something similar. But there are other reasons for invalidity as well, like: there is already a face connecting the given vertices.
Note that the given vertices have to be in front-face counter-clockwise order, just as with addFace()
. See addFace()
for more information about this.
|
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 in lvr2::HalfEdgeMesh< BaseVecT >.
|
pure 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.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
pure 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.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
pure 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.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
virtual |
Returns the number of adjacent faces to the given edge.
This functions always returns one of 0, 1 or 2.
|
pure virtual |
Returns the number of edges in the mesh.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
pure virtual |
Returns the number of faces in the mesh.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
pure virtual |
Returns the number of vertices in the mesh.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
pure virtual |
Removes the given face and all (if not connected to any other face/edge/vertex) connected edges and vertices.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
virtual |
Method for usage in range-based for-loops.
Returns a simple proxy object that uses verticesBegin()
and verticesEnd()
.
|
pure virtual |
Returns an iterator to the first vertex of this mesh.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.
|
pure virtual |
Returns an iterator to the element following the last vertex of this mesh.
Implemented in lvr2::HalfEdgeMesh< BaseVecT >.