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 
422  virtual MeshHandleIteratorPtr<VertexHandle> verticesBegin() const = 0;
423 
427  virtual MeshHandleIteratorPtr<VertexHandle> verticesEnd() const = 0;
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 
534  virtual OptionalFaceHandle getFaceBetween(VertexHandle aH, VertexHandle bH, VertexHandle cH) const;
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 
583  virtual OptionalVertexHandle getVertexBetween(EdgeHandle aH, EdgeHandle bH) const;
584 
589  virtual OptionalEdgeHandle getEdgeBetween(VertexHandle aH, VertexHandle bH) const;
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;
620 
621  FaceIteratorProxy(const BaseMesh<BaseVecT>& mesh) : m_mesh(mesh) {}
622  private:
625 };
626 
627 template <typename BaseVecT>
628 class EdgeIteratorProxy
629 {
630 public:
631  MeshHandleIteratorPtr<EdgeHandle> begin() const;
633 
634  EdgeIteratorProxy(const BaseMesh<BaseVecT>& mesh) : m_mesh(mesh) {}
635  private:
638 };
639 
640 template <typename BaseVecT>
642 {
643 public:
646 
647  VertexIteratorProxy(const BaseMesh<BaseVecT>& mesh) : m_mesh(mesh) {}
648  private:
651 };
652 
654 {
657 
659  std::array<EdgeHandle, 2> removedEdges;
660 
663 
665  FaceHandle removedFace,
666  std::array<EdgeHandle, 2> removedEdges,
667  EdgeHandle newEdge
668  ) : removedFace(removedFace), removedEdges(removedEdges), newEdge(newEdge) {};
669 };
670 
672 {
675 
677 
681  std::array<boost::optional<EdgeCollapseRemovedFace>, 2> neighbors;
682 
683  EdgeCollapseResult(VertexHandle midPoint, VertexHandle removedPoint) : midPoint(midPoint), removedPoint(removedPoint) {};
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_ */
FaceIteratorProxy(const BaseMesh< BaseVecT > &mesh)
Definition: BaseMesh.hpp:621
A wrapper for the MeshHandleIterator to save beloved future programmers from dereferencing too much <...
Definition: BaseMesh.hpp:81
EdgeCollapseResult(VertexHandle midPoint, VertexHandle removedPoint)
Definition: BaseMesh.hpp:683
MeshHandleIteratorPtr(std::unique_ptr< MeshHandleIterator< HandleT >> iter)
Definition: BaseMesh.hpp:84
VertexHandle midPoint
The vertex which was inserted to replace the collapsed edge.
Definition: BaseMesh.hpp:674
const BaseMesh< BaseVecT > & m_mesh
Definition: BaseMesh.hpp:623
Handle to access vertices of the mesh.
Definition: Handles.hpp:146
HalfEdgeMesh< Vec > mesh
EdgeHandle newEdge
The edge that was inserted to replace the removed face.
Definition: BaseMesh.hpp:662
virtual bool operator!=(const MeshHandleIterator &other) const =0
VertexHandle edgeCenter
Definition: BaseMesh.hpp:690
std::unique_ptr< MeshHandleIterator< HandleT > > m_iter
Definition: BaseMesh.hpp:92
Handle to access edges of the mesh.
Definition: Handles.hpp:134
const BaseMesh< BaseVecT > & m_mesh
Definition: BaseMesh.hpp:649
virtual bool operator==(const MeshHandleIterator &other) const =0
VertexIteratorProxy(const BaseMesh< BaseVecT > &mesh)
Definition: BaseMesh.hpp:647
uint32_t Index
Datatype used as index for each vertex, face and edge.
Definition: Handles.hpp:96
const BaseMesh< BaseVecT > & m_mesh
Definition: BaseMesh.hpp:636
std::array< boost::optional< EdgeCollapseRemovedFace >, 2 > neighbors
Definition: BaseMesh.hpp:681
Semantically equivalent to boost::optional<VertexHandle>
Definition: Handles.hpp:176
Interface for triangle-meshes with adjacency information.
Definition: BaseMesh.hpp:140
virtual ~BaseMesh()
Definition: BaseMesh.hpp:144
VertexSplitResult(VertexHandle longestEdgeCenter)
Definition: BaseMesh.hpp:693
FaceHandle removedFace
A face adjacent to the collapsed edge which was removed.
Definition: BaseMesh.hpp:656
virtual HandleT operator*() const =0
Returns the current handle.
VertexHandle removedPoint
Definition: BaseMesh.hpp:676
EdgeIteratorProxy(const BaseMesh< BaseVecT > &mesh)
Definition: BaseMesh.hpp:634
Semantically equivalent to boost::optional<FaceHandle>
Definition: Handles.hpp:170
An iterator for handles in the BaseMesh.
Definition: BaseMesh.hpp:61
virtual MeshHandleIterator & operator++()=0
std::array< EdgeHandle, 2 > removedEdges
The edges of the removed face (excluding the collapsed edge itself)
Definition: BaseMesh.hpp:659
EdgeSplitResult(VertexHandle longestEdgeCenter)
Definition: BaseMesh.hpp:702
EdgeCollapseRemovedFace(FaceHandle removedFace, std::array< EdgeHandle, 2 > removedEdges, EdgeHandle newEdge)
Definition: BaseMesh.hpp:664
std::vector< FaceHandle > addedFaces
Definition: BaseMesh.hpp:691
virtual ~MeshHandleIterator()=default
std::vector< FaceHandle > addedFaces
Definition: BaseMesh.hpp:700
VertexHandle edgeCenter
Definition: BaseMesh.hpp:699
Handle to access faces of the mesh.
Definition: Handles.hpp:140
Semantically equivalent to boost::optional<EdgeHandle>
Definition: Handles.hpp:164


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 Mon Feb 28 2022 22:46:06