BaseMesh.hpp
Go to the documentation of this file.
1 
28 /*
29  * BaseMesh.hpp
30  *
31  * @date 02.06.2017
32  * @author Lukas Kalbertodt <lukas.kalbertodt@gmail.com>
33  */
34 
35 #ifndef LVR2_GEOMETRY_BASEMESH_H_
36 #define LVR2_GEOMETRY_BASEMESH_H_
37 
38 #include <cstdint>
39 #include <array>
40 #include <vector>
41 #include <type_traits>
42 #include <memory>
43 #include <boost/optional.hpp>
44 
45 
46 
47 #include "Handles.hpp"
48 
49 namespace lvr2
50 {
51 
60 template<typename HandleT>
62 {
63  static_assert(std::is_base_of<BaseHandle<Index>, HandleT>::value, "HandleT must inherit from BaseHandle!");
64 public:
67  virtual MeshHandleIterator& operator++() = 0;
68  virtual bool operator==(const MeshHandleIterator& other) const = 0;
69  virtual bool operator!=(const MeshHandleIterator& other) const = 0;
70 
72  virtual HandleT operator*() const = 0;
73 
74  virtual ~MeshHandleIterator() = default;
75 
76  using HandleType = HandleT;
77 };
78 
80 template<typename HandleT>
82 {
83 public:
84  MeshHandleIteratorPtr(std::unique_ptr<MeshHandleIterator<HandleT>> iter) : m_iter(std::move(iter)) {};
86  bool operator==(const MeshHandleIteratorPtr& other) const;
87  bool operator!=(const MeshHandleIteratorPtr& other) const;
88  HandleT operator*() const;
89 
90  using HandleType = HandleT;
91 private:
92  std::unique_ptr<MeshHandleIterator<HandleT>> m_iter;
93 };
94 
95 // Forward declaration
96 template <typename> class FaceIteratorProxy;
97 template <typename> class EdgeIteratorProxy;
98 template <typename> class VertexIteratorProxy;
99 
100 struct EdgeCollapseResult;
102 
139 template<typename BaseVecT>
140 class BaseMesh
141 {
142 public:
143 
144  virtual ~BaseMesh() {}
145 
146  // =======================================================================
147  // Pure virtual methods (need to be implemented)
148  // =======================================================================
149 
158  virtual VertexHandle addVertex(BaseVecT pos) = 0;
159 
174  virtual FaceHandle addFace(VertexHandle v1, VertexHandle v2, VertexHandle v3) = 0;
175 
180  virtual void removeFace(FaceHandle handle) = 0;
181 
193  virtual EdgeCollapseResult collapseEdge(EdgeHandle edgeH) = 0;
194 
216  virtual void flipEdge(EdgeHandle edgeH) = 0;
217 
221  virtual size_t numVertices() const = 0;
222 
226  virtual size_t numFaces() const = 0;
227 
231  virtual size_t numEdges() const = 0;
232 
236  virtual bool containsVertex(VertexHandle vH) const = 0;
237 
241  virtual bool containsFace(FaceHandle vH) const = 0;
242 
246  virtual bool containsEdge(EdgeHandle vH) const = 0;
247 
255  virtual Index nextVertexIndex() const = 0;
256 
264  virtual Index nextFaceIndex() const = 0;
265 
273  virtual Index nextEdgeIndex() const = 0;
274 
278  virtual BaseVecT getVertexPosition(VertexHandle handle) const = 0;
279 
283  virtual BaseVecT& getVertexPosition(VertexHandle handle) = 0;
284 
290  virtual std::array<VertexHandle, 3> getVerticesOfFace(FaceHandle handle) const = 0;
291 
297  virtual std::array<EdgeHandle, 3> getEdgesOfFace(FaceHandle handle) const = 0;
298 
316  virtual void getNeighboursOfFace(FaceHandle handle, std::vector<FaceHandle>& facesOut) const = 0;
317 
323  virtual std::array<VertexHandle, 2> getVerticesOfEdge(EdgeHandle edgeH) const = 0;
324 
330  virtual std::array<OptionalFaceHandle, 2> getFacesOfEdge(EdgeHandle edgeH) const = 0;
331 
347  virtual void getFacesOfVertex(VertexHandle handle, std::vector<FaceHandle>& facesOut) const = 0;
348 
364  virtual void getEdgesOfVertex(VertexHandle handle, std::vector<EdgeHandle>& edgesOut) const = 0;
365 
382  virtual void getNeighboursOfVertex(VertexHandle handle, std::vector<VertexHandle>& verticesOut) const = 0;
383 
393  virtual OptionalFaceHandle getOppositeFace(FaceHandle faceH, VertexHandle vertexH) const = 0;
394 
404  virtual OptionalEdgeHandle getOppositeEdge(FaceHandle faceH, VertexHandle vertexH) const = 0;
405 
415  virtual OptionalVertexHandle getOppositeVertex(FaceHandle faceH, EdgeHandle edgeH) const = 0;
416 
423 
428 
434  virtual MeshHandleIteratorPtr<FaceHandle> facesBegin() const = 0;
435 
439  virtual MeshHandleIteratorPtr<FaceHandle> facesEnd() const = 0;
440 
446  virtual MeshHandleIteratorPtr<EdgeHandle> edgesBegin() const = 0;
447 
451  virtual MeshHandleIteratorPtr<EdgeHandle> edgesEnd() const = 0;
452 
453  // =======================================================================
454  // Provided methods (already implemented)
455  // =======================================================================
456 
462  virtual std::array<BaseVecT, 3> getVertexPositionsOfFace(FaceHandle handle) const;
463 
467  BaseVecT calcFaceCentroid(FaceHandle handle) const;
468 
472  typename BaseVecT::CoordType calcFaceArea(FaceHandle handle) const;
473 
484  virtual std::vector<FaceHandle> getNeighboursOfFace(FaceHandle handle) const;
485 
494  virtual bool isCollapsable(EdgeHandle handle) const;
495 
503  virtual bool isFlippable(EdgeHandle handle) const;
504 
509  virtual bool isBorderEdge(EdgeHandle handle) const = 0;
510 
524  virtual bool isFaceInsertionValid(VertexHandle v1, VertexHandle v2, VertexHandle v3) const;
525 
535 
541  virtual uint8_t numAdjacentFaces(EdgeHandle handle) const;
542 
553  virtual std::vector<FaceHandle> getFacesOfVertex(VertexHandle handle) const;
554 
565  virtual std::vector<EdgeHandle> getEdgesOfVertex(VertexHandle handle) const;
566 
577  virtual std::vector<VertexHandle> getNeighboursOfVertex(VertexHandle handle) const;
578 
584 
590 
596  virtual FaceIteratorProxy<BaseVecT> faces() const;
597 
603  virtual EdgeIteratorProxy<BaseVecT> edges() const;
604 
610  virtual VertexIteratorProxy<BaseVecT> vertices() const;
611 
612 };
613 
614 template <typename BaseVecT>
615 class FaceIteratorProxy
616 {
617 public:
618  MeshHandleIteratorPtr<FaceHandle> begin() const;
619  MeshHandleIteratorPtr<FaceHandle> end() const;
620 
622  private:
625 };
626 
627 template <typename BaseVecT>
628 class EdgeIteratorProxy
629 {
630 public:
633 
635  private:
638 };
639 
640 template <typename BaseVecT>
642 {
643 public:
646 
648  private:
651 };
652 
654 {
657 
659  std::array<EdgeHandle, 2> removedEdges;
660 
663 
666  std::array<EdgeHandle, 2> removedEdges,
669 };
670 
672 {
675 
677 
681  std::array<boost::optional<EdgeCollapseRemovedFace>, 2> neighbors;
682 
684 };
685 
686 
688 {
689 
691  std::vector<FaceHandle> addedFaces;
692 
693  VertexSplitResult(VertexHandle longestEdgeCenter) : edgeCenter(longestEdgeCenter) {};
694 };
695 
697 {
698 
700  std::vector<FaceHandle> addedFaces;
701 
702  EdgeSplitResult(VertexHandle longestEdgeCenter) : edgeCenter(longestEdgeCenter) {};
703 };
704 
705 } // namespace lvr2
706 
707 #include "lvr2/geometry/BaseMesh.tcc"
708 
709 #endif /* LVR2_GEOMETRY_BASEMESH_H_ */
lvr2::MeshHandleIteratorPtr::operator==
bool operator==(const MeshHandleIteratorPtr &other) const
lvr2::BaseMesh::getFacesOfVertex
virtual void getFacesOfVertex(VertexHandle handle, std::vector< FaceHandle > &facesOut) const =0
Get a list of faces the given vertex belongs to.
Handles.hpp
lvr2::BaseMesh::edges
virtual EdgeIteratorProxy< BaseVecT > edges() const
Method for usage in range-based for-loops.
lvr2::MeshHandleIteratorPtr::operator!=
bool operator!=(const MeshHandleIteratorPtr &other) const
lvr2::MeshHandleIterator::operator++
virtual MeshHandleIterator & operator++()=0
lvr2::BaseMesh::getEdgesOfFace
virtual std::array< EdgeHandle, 3 > getEdgesOfFace(FaceHandle handle) const =0
Get the three edges surrounding the given face.
lvr2::MeshHandleIterator
An iterator for handles in the BaseMesh.
Definition: BaseMesh.hpp:61
lvr2::MeshHandleIterator::operator!=
virtual bool operator!=(const MeshHandleIterator &other) const =0
lvr2::BaseMesh::getNeighboursOfVertex
virtual void getNeighboursOfVertex(VertexHandle handle, std::vector< VertexHandle > &verticesOut) const =0
Get vertex handles of the neighbours of the requested vertex.
lvr2::BaseMesh::vertices
virtual VertexIteratorProxy< BaseVecT > vertices() const
Method for usage in range-based for-loops.
lvr2::EdgeIteratorProxy
Definition: BaseMesh.hpp:97
lvr2::BaseMesh::edgesBegin
virtual MeshHandleIteratorPtr< EdgeHandle > edgesBegin() const =0
Returns an iterator to the first edge of this mesh.
lvr2::MeshHandleIteratorPtr::MeshHandleIteratorPtr
MeshHandleIteratorPtr(std::unique_ptr< MeshHandleIterator< HandleT >> iter)
Definition: BaseMesh.hpp:84
lvr2::FaceHandle
Handle to access faces of the mesh.
Definition: Handles.hpp:140
lvr2::BaseMesh::edgesEnd
virtual MeshHandleIteratorPtr< EdgeHandle > edgesEnd() const =0
Returns an iterator to the element following the last edge of this mesh.
lvr2::EdgeCollapseResult::neighbors
std::array< boost::optional< EdgeCollapseRemovedFace >, 2 > neighbors
Definition: BaseMesh.hpp:681
lvr2::BaseMesh::nextVertexIndex
virtual Index nextVertexIndex() const =0
Returns the handle index which would be assigned to the next vertex that is created....
lvr2::BaseMesh::getOppositeEdge
virtual OptionalEdgeHandle getOppositeEdge(FaceHandle faceH, VertexHandle vertexH) const =0
Get the optional edge handle of the edge lying on the vertex's opposite site.
lvr2::VertexSplitResult::edgeCenter
VertexHandle edgeCenter
Definition: BaseMesh.hpp:690
lvr2::BaseMesh::getEdgeBetween
virtual OptionalEdgeHandle getEdgeBetween(VertexHandle aH, VertexHandle bH) const
If the two given vertices are connected by an edge, it is returned. None otherwise.
lvr2::EdgeCollapseResult::removedPoint
VertexHandle removedPoint
Definition: BaseMesh.hpp:676
lvr2::OptionalVertexHandle
Semantically equivalent to boost::optional<VertexHandle>
Definition: Handles.hpp:176
lvr2::BaseHandle< Index >
lvr2::BaseMesh::containsEdge
virtual bool containsEdge(EdgeHandle vH) const =0
Checks if the given edge is part of this mesh.
lvr2::EdgeCollapseResult::midPoint
VertexHandle midPoint
The vertex which was inserted to replace the collapsed edge.
Definition: BaseMesh.hpp:674
lvr2::EdgeCollapseRemovedFace::removedEdges
std::array< EdgeHandle, 2 > removedEdges
The edges of the removed face (excluding the collapsed edge itself)
Definition: BaseMesh.hpp:659
lvr2::BaseMesh::~BaseMesh
virtual ~BaseMesh()
Definition: BaseMesh.hpp:144
lvr2::EdgeIteratorProxy::begin
MeshHandleIteratorPtr< EdgeHandle > begin() const
lvr2::BaseMesh::collapseEdge
virtual EdgeCollapseResult collapseEdge(EdgeHandle edgeH)=0
Merges the two vertices connected by the given edge.
lvr2::BaseMesh::removeFace
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...
lvr2::FaceIteratorProxy
Definition: BaseMesh.hpp:96
lvr2::EdgeSplitResult::EdgeSplitResult
EdgeSplitResult(VertexHandle longestEdgeCenter)
Definition: BaseMesh.hpp:702
lvr2::EdgeCollapseResult::EdgeCollapseResult
EdgeCollapseResult(VertexHandle midPoint, VertexHandle removedPoint)
Definition: BaseMesh.hpp:683
lvr2::EdgeCollapseRemovedFace::newEdge
EdgeHandle newEdge
The edge that was inserted to replace the removed face.
Definition: BaseMesh.hpp:662
lvr2::BaseMesh::facesEnd
virtual MeshHandleIteratorPtr< FaceHandle > facesEnd() const =0
Returns an iterator to the element following the last face of this mesh.
lvr2::VertexIteratorProxy::m_mesh
const BaseMesh< BaseVecT > & m_mesh
Definition: BaseMesh.hpp:649
lvr2::FaceIteratorProxy::FaceIteratorProxy
FaceIteratorProxy(const BaseMesh< BaseVecT > &mesh)
Definition: BaseMesh.hpp:621
lvr2::EdgeHandle
Handle to access edges of the mesh.
Definition: Handles.hpp:134
lvr2::BaseMesh::getFaceBetween
virtual OptionalFaceHandle getFaceBetween(VertexHandle aH, VertexHandle bH, VertexHandle cH) const
If all vertices are part of one face, this face is returned. None otherwise.
lvr2::VertexSplitResult::addedFaces
std::vector< FaceHandle > addedFaces
Definition: BaseMesh.hpp:691
lvr2::OptionalEdgeHandle
Semantically equivalent to boost::optional<EdgeHandle>
Definition: Handles.hpp:164
lvr2::EdgeCollapseRemovedFace::EdgeCollapseRemovedFace
EdgeCollapseRemovedFace(FaceHandle removedFace, std::array< EdgeHandle, 2 > removedEdges, EdgeHandle newEdge)
Definition: BaseMesh.hpp:664
lvr2::BaseMesh::getFacesOfEdge
virtual std::array< OptionalFaceHandle, 2 > getFacesOfEdge(EdgeHandle edgeH) const =0
Get the two faces of an edge.
lvr2::VertexSplitResult
Definition: BaseMesh.hpp:687
lvr2::EdgeSplitResult::edgeCenter
VertexHandle edgeCenter
Definition: BaseMesh.hpp:699
lvr2::MeshHandleIteratorPtr::HandleType
HandleT HandleType
Definition: BaseMesh.hpp:90
lvr2::BaseMesh::isBorderEdge
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.
lvr2::BaseMesh::numFaces
virtual size_t numFaces() const =0
Returns the number of faces in the mesh.
lvr2::OptionalFaceHandle
Semantically equivalent to boost::optional<FaceHandle>
Definition: Handles.hpp:170
lvr2::FaceIteratorProxy::begin
MeshHandleIteratorPtr< FaceHandle > begin() const
lvr2::BaseMesh::getOppositeFace
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.
lvr2::BaseMesh::getVerticesOfFace
virtual std::array< VertexHandle, 3 > getVerticesOfFace(FaceHandle handle) const =0
Get the three vertices surrounding the given face.
lvr2::VertexHandle
Handle to access vertices of the mesh.
Definition: Handles.hpp:146
lvr2::EdgeSplitResult::addedFaces
std::vector< FaceHandle > addedFaces
Definition: BaseMesh.hpp:700
lvr2::BaseMesh::isFlippable
virtual bool isFlippable(EdgeHandle handle) const
Determines whether or not the given edge can be flipped without destroying the mesh.
lvr2::VertexIteratorProxy::VertexIteratorProxy
VertexIteratorProxy(const BaseMesh< BaseVecT > &mesh)
Definition: BaseMesh.hpp:647
lvr2::BaseMesh::numVertices
virtual size_t numVertices() const =0
Returns the number of vertices in the mesh.
lvr2::EdgeIteratorProxy::EdgeIteratorProxy
EdgeIteratorProxy(const BaseMesh< BaseVecT > &mesh)
Definition: BaseMesh.hpp:634
lvr2::BaseMesh::calcFaceCentroid
BaseVecT calcFaceCentroid(FaceHandle handle) const
Calc and return the centroid of the requested face.
lvr2::BaseMesh::nextEdgeIndex
virtual Index nextEdgeIndex() const =0
Returns the handle index which would be assigned to the next edge that is created....
lvr2::MeshHandleIterator::~MeshHandleIterator
virtual ~MeshHandleIterator()=default
lvr2::BaseMesh::addVertex
virtual VertexHandle addVertex(BaseVecT pos)=0
Adds a vertex with the given position to the mesh.
lvr2::MeshHandleIterator::operator*
virtual HandleT operator*() const =0
Returns the current handle.
lvr2::BaseMesh::getVertexBetween
virtual OptionalVertexHandle getVertexBetween(EdgeHandle aH, EdgeHandle bH) const
If the given edges share a vertex, it is returned. None otherwise.
lvr2::EdgeCollapseRemovedFace
Definition: BaseMesh.hpp:653
lvr2::VertexIteratorProxy
Definition: BaseMesh.hpp:98
lvr2::BaseMesh::getVerticesOfEdge
virtual std::array< VertexHandle, 2 > getVerticesOfEdge(EdgeHandle edgeH) const =0
Get the two vertices of an edge.
lvr2::BaseMesh::numAdjacentFaces
virtual uint8_t numAdjacentFaces(EdgeHandle handle) const
Returns the number of adjacent faces to the given edge.
lvr2::BaseMesh::facesBegin
virtual MeshHandleIteratorPtr< FaceHandle > facesBegin() const =0
Returns an iterator to the first face of this mesh.
lvr2::BaseMesh::getOppositeVertex
virtual OptionalVertexHandle getOppositeVertex(FaceHandle faceH, EdgeHandle edgeH) const =0
Get the optional vertex handle of the vertex lying on the edge's opposite site.
lvr2::EdgeCollapseResult
Definition: BaseMesh.hpp:671
lvr2::BaseMesh::calcFaceArea
BaseVecT::CoordType calcFaceArea(FaceHandle handle) const
Calc and return the area of the requested face.
lvr2::BaseMesh::verticesBegin
virtual MeshHandleIteratorPtr< VertexHandle > verticesBegin() const =0
Returns an iterator to the first vertex of this mesh.
lvr2::MeshHandleIteratorPtr::m_iter
std::unique_ptr< MeshHandleIterator< HandleT > > m_iter
Definition: BaseMesh.hpp:92
lvr2::BaseMesh::getVertexPositionsOfFace
virtual std::array< BaseVecT, 3 > getVertexPositionsOfFace(FaceHandle handle) const
Get the points of the requested face.
lvr2::BaseMesh::addFace
virtual FaceHandle addFace(VertexHandle v1, VertexHandle v2, VertexHandle v3)=0
Creates a face connecting the three given vertices.
std
Definition: HalfEdge.hpp:124
lvr2
Definition: BaseBufferManipulators.hpp:39
lvr2::VertexSplitResult::VertexSplitResult
VertexSplitResult(VertexHandle longestEdgeCenter)
Definition: BaseMesh.hpp:693
lvr2::VertexIteratorProxy::begin
MeshHandleIteratorPtr< VertexHandle > begin() const
lvr2::MeshHandleIteratorPtr::operator*
HandleT operator*() const
lvr2::BaseMesh::containsVertex
virtual bool containsVertex(VertexHandle vH) const =0
Checks if the given vertex is part of this mesh.
lvr2::BaseMesh::getVertexPosition
virtual BaseVecT getVertexPosition(VertexHandle handle) const =0
Get the position of the given vertex.
lvr2::VertexIteratorProxy::end
MeshHandleIteratorPtr< VertexHandle > end() const
lvr2::BaseMesh::faces
virtual FaceIteratorProxy< BaseVecT > faces() const
Method for usage in range-based for-loops.
lvr2::BaseMesh::isFaceInsertionValid
virtual bool isFaceInsertionValid(VertexHandle v1, VertexHandle v2, VertexHandle v3) const
Check whether or not inserting a face between the given vertices would be valid.
lvr2::BaseMesh
Interface for triangle-meshes with adjacency information.
Definition: BaseMesh.hpp:140
lvr2::BaseMesh::numEdges
virtual size_t numEdges() const =0
Returns the number of edges in the mesh.
lvr2::FaceIteratorProxy::end
MeshHandleIteratorPtr< FaceHandle > end() const
lvr2::BaseMesh::containsFace
virtual bool containsFace(FaceHandle vH) const =0
Checks if the given face is part of this mesh.
lvr2::BaseMesh::verticesEnd
virtual MeshHandleIteratorPtr< VertexHandle > verticesEnd() const =0
Returns an iterator to the element following the last vertex of this mesh.
lvr2::Index
uint32_t Index
Datatype used as index for each vertex, face and edge.
Definition: Handles.hpp:96
lvr2::BaseMesh::flipEdge
virtual void flipEdge(EdgeHandle edgeH)=0
Performs the edge flip operation.
lvr2::EdgeIteratorProxy::m_mesh
const BaseMesh< BaseVecT > & m_mesh
Definition: BaseMesh.hpp:636
lvr2::BaseMesh::nextFaceIndex
virtual Index nextFaceIndex() const =0
Returns the handle index which would be assigned to the next face that is created....
lvr2::EdgeSplitResult
Definition: BaseMesh.hpp:696
lvr2::BaseMesh::getEdgesOfVertex
virtual void getEdgesOfVertex(VertexHandle handle, std::vector< EdgeHandle > &edgesOut) const =0
Get a list of edges around the given vertex.
mesh
HalfEdgeMesh< Vec > mesh
Definition: src/tools/lvr2_gs_reconstruction/Main.cpp:26
lvr2::MeshHandleIteratorPtr
A wrapper for the MeshHandleIterator to save beloved future programmers from dereferencing too much <...
Definition: BaseMesh.hpp:81
lvr2::BaseMesh::getNeighboursOfFace
virtual void getNeighboursOfFace(FaceHandle handle, std::vector< FaceHandle > &facesOut) const =0
Get face handles of the neighbours of the requested face.
lvr2::BaseMesh::isCollapsable
virtual bool isCollapsable(EdgeHandle handle) const
Determines whether or not an edge collapse of the given edge is possible without creating invalid mes...
lvr2::EdgeIteratorProxy::end
MeshHandleIteratorPtr< EdgeHandle > end() const
lvr2::MeshHandleIteratorPtr::operator++
MeshHandleIteratorPtr & operator++()
lvr2::MeshHandleIterator::operator==
virtual bool operator==(const MeshHandleIterator &other) const =0
lvr2::EdgeCollapseRemovedFace::removedFace
FaceHandle removedFace
A face adjacent to the collapsed edge which was removed.
Definition: BaseMesh.hpp:656
lvr2::FaceIteratorProxy::m_mesh
const BaseMesh< BaseVecT > & m_mesh
Definition: BaseMesh.hpp:623


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