Go to the documentation of this file.
35 #ifndef LVR2_GEOMETRY_BASEMESH_H_
36 #define LVR2_GEOMETRY_BASEMESH_H_
41 #include <type_traits>
43 #include <boost/optional.hpp>
60 template<
typename HandleT>
63 static_assert(std::is_base_of<
BaseHandle<Index>, HandleT>::value,
"HandleT must inherit from BaseHandle!");
80 template<
typename HandleT>
92 std::unique_ptr<MeshHandleIterator<HandleT>>
m_iter;
139 template<
typename BaseVecT>
226 virtual size_t numFaces()
const = 0;
231 virtual size_t numEdges()
const = 0;
614 template <
typename BaseVecT>
615 class FaceIteratorProxy
618 MeshHandleIteratorPtr<FaceHandle>
begin()
const;
619 MeshHandleIteratorPtr<FaceHandle>
end()
const;
627 template <
typename BaseVecT>
640 template <
typename BaseVecT>
681 std::array<boost::optional<EdgeCollapseRemovedFace>, 2>
neighbors;
707 #include "lvr2/geometry/BaseMesh.tcc"
bool operator==(const MeshHandleIteratorPtr &other) const
virtual void getFacesOfVertex(VertexHandle handle, std::vector< FaceHandle > &facesOut) const =0
Get a list of faces the given vertex belongs to.
virtual EdgeIteratorProxy< BaseVecT > edges() const
Method for usage in range-based for-loops.
bool operator!=(const MeshHandleIteratorPtr &other) const
virtual MeshHandleIterator & operator++()=0
virtual std::array< EdgeHandle, 3 > getEdgesOfFace(FaceHandle handle) const =0
Get the three edges surrounding the given face.
An iterator for handles in the BaseMesh.
virtual bool operator!=(const MeshHandleIterator &other) const =0
virtual void getNeighboursOfVertex(VertexHandle handle, std::vector< VertexHandle > &verticesOut) const =0
Get vertex handles of the neighbours of the requested vertex.
virtual VertexIteratorProxy< BaseVecT > vertices() const
Method for usage in range-based for-loops.
virtual MeshHandleIteratorPtr< EdgeHandle > edgesBegin() const =0
Returns an iterator to the first edge of this mesh.
MeshHandleIteratorPtr(std::unique_ptr< MeshHandleIterator< HandleT >> iter)
Handle to access faces of the mesh.
virtual MeshHandleIteratorPtr< EdgeHandle > edgesEnd() const =0
Returns an iterator to the element following the last edge of this mesh.
std::array< boost::optional< EdgeCollapseRemovedFace >, 2 > neighbors
virtual Index nextVertexIndex() const =0
Returns the handle index which would be assigned to the next vertex that is created....
virtual OptionalEdgeHandle getOppositeEdge(FaceHandle faceH, VertexHandle vertexH) const =0
Get the optional edge handle of the edge lying on the vertex's opposite site.
virtual OptionalEdgeHandle getEdgeBetween(VertexHandle aH, VertexHandle bH) const
If the two given vertices are connected by an edge, it is returned. None otherwise.
VertexHandle removedPoint
Semantically equivalent to boost::optional<VertexHandle>
virtual bool containsEdge(EdgeHandle vH) const =0
Checks if the given edge is part of this mesh.
VertexHandle midPoint
The vertex which was inserted to replace the collapsed edge.
std::array< EdgeHandle, 2 > removedEdges
The edges of the removed face (excluding the collapsed edge itself)
MeshHandleIteratorPtr< EdgeHandle > begin() const
virtual EdgeCollapseResult collapseEdge(EdgeHandle edgeH)=0
Merges the two vertices connected by the given edge.
virtual void removeFace(FaceHandle handle)=0
Removes the given face and all (if not connected to any other face/edge/vertex) connected edges and v...
EdgeSplitResult(VertexHandle longestEdgeCenter)
EdgeCollapseResult(VertexHandle midPoint, VertexHandle removedPoint)
EdgeHandle newEdge
The edge that was inserted to replace the removed face.
virtual MeshHandleIteratorPtr< FaceHandle > facesEnd() const =0
Returns an iterator to the element following the last face of this mesh.
const BaseMesh< BaseVecT > & m_mesh
FaceIteratorProxy(const BaseMesh< BaseVecT > &mesh)
Handle to access edges of the mesh.
virtual OptionalFaceHandle getFaceBetween(VertexHandle aH, VertexHandle bH, VertexHandle cH) const
If all vertices are part of one face, this face is returned. None otherwise.
std::vector< FaceHandle > addedFaces
Semantically equivalent to boost::optional<EdgeHandle>
EdgeCollapseRemovedFace(FaceHandle removedFace, std::array< EdgeHandle, 2 > removedEdges, EdgeHandle newEdge)
virtual std::array< OptionalFaceHandle, 2 > getFacesOfEdge(EdgeHandle edgeH) const =0
Get the two faces of an edge.
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.
virtual size_t numFaces() const =0
Returns the number of faces in the mesh.
Semantically equivalent to boost::optional<FaceHandle>
MeshHandleIteratorPtr< FaceHandle > begin() const
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.
virtual std::array< VertexHandle, 3 > getVerticesOfFace(FaceHandle handle) const =0
Get the three vertices surrounding the given face.
Handle to access vertices of the mesh.
std::vector< FaceHandle > addedFaces
virtual bool isFlippable(EdgeHandle handle) const
Determines whether or not the given edge can be flipped without destroying the mesh.
VertexIteratorProxy(const BaseMesh< BaseVecT > &mesh)
virtual size_t numVertices() const =0
Returns the number of vertices in the mesh.
EdgeIteratorProxy(const BaseMesh< BaseVecT > &mesh)
BaseVecT calcFaceCentroid(FaceHandle handle) const
Calc and return the centroid of the requested face.
virtual Index nextEdgeIndex() const =0
Returns the handle index which would be assigned to the next edge that is created....
virtual ~MeshHandleIterator()=default
virtual VertexHandle addVertex(BaseVecT pos)=0
Adds a vertex with the given position to the mesh.
virtual HandleT operator*() const =0
Returns the current handle.
virtual OptionalVertexHandle getVertexBetween(EdgeHandle aH, EdgeHandle bH) const
If the given edges share a vertex, it is returned. None otherwise.
virtual std::array< VertexHandle, 2 > getVerticesOfEdge(EdgeHandle edgeH) const =0
Get the two vertices of an edge.
virtual uint8_t numAdjacentFaces(EdgeHandle handle) const
Returns the number of adjacent faces to the given edge.
virtual MeshHandleIteratorPtr< FaceHandle > facesBegin() const =0
Returns an iterator to the first face of this mesh.
virtual OptionalVertexHandle getOppositeVertex(FaceHandle faceH, EdgeHandle edgeH) const =0
Get the optional vertex handle of the vertex lying on the edge's opposite site.
BaseVecT::CoordType calcFaceArea(FaceHandle handle) const
Calc and return the area of the requested face.
virtual MeshHandleIteratorPtr< VertexHandle > verticesBegin() const =0
Returns an iterator to the first vertex of this mesh.
std::unique_ptr< MeshHandleIterator< HandleT > > m_iter
virtual std::array< BaseVecT, 3 > getVertexPositionsOfFace(FaceHandle handle) const
Get the points of the requested face.
virtual FaceHandle addFace(VertexHandle v1, VertexHandle v2, VertexHandle v3)=0
Creates a face connecting the three given vertices.
VertexSplitResult(VertexHandle longestEdgeCenter)
MeshHandleIteratorPtr< VertexHandle > begin() const
HandleT operator*() const
virtual bool containsVertex(VertexHandle vH) const =0
Checks if the given vertex is part of this mesh.
virtual BaseVecT getVertexPosition(VertexHandle handle) const =0
Get the position of the given vertex.
MeshHandleIteratorPtr< VertexHandle > end() const
virtual FaceIteratorProxy< BaseVecT > faces() const
Method for usage in range-based for-loops.
virtual bool isFaceInsertionValid(VertexHandle v1, VertexHandle v2, VertexHandle v3) const
Check whether or not inserting a face between the given vertices would be valid.
Interface for triangle-meshes with adjacency information.
virtual size_t numEdges() const =0
Returns the number of edges in the mesh.
MeshHandleIteratorPtr< FaceHandle > end() const
virtual bool containsFace(FaceHandle vH) const =0
Checks if the given face is part of this mesh.
virtual MeshHandleIteratorPtr< VertexHandle > verticesEnd() const =0
Returns an iterator to the element following the last vertex of this mesh.
uint32_t Index
Datatype used as index for each vertex, face and edge.
virtual void flipEdge(EdgeHandle edgeH)=0
Performs the edge flip operation.
const BaseMesh< BaseVecT > & m_mesh
virtual Index nextFaceIndex() const =0
Returns the handle index which would be assigned to the next face that is created....
virtual void getEdgesOfVertex(VertexHandle handle, std::vector< EdgeHandle > &edgesOut) const =0
Get a list of edges around the given vertex.
A wrapper for the MeshHandleIterator to save beloved future programmers from dereferencing too much <...
virtual void getNeighboursOfFace(FaceHandle handle, std::vector< FaceHandle > &facesOut) const =0
Get face handles of the neighbours of the requested face.
virtual bool isCollapsable(EdgeHandle handle) const
Determines whether or not an edge collapse of the given edge is possible without creating invalid mes...
MeshHandleIteratorPtr< EdgeHandle > end() const
MeshHandleIteratorPtr & operator++()
virtual bool operator==(const MeshHandleIterator &other) const =0
FaceHandle removedFace
A face adjacent to the collapsed edge which was removed.
const BaseMesh< BaseVecT > & m_mesh
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:22