Base class for the half-edge mesh. More...
#include <mesh_base.h>
Public Types | |
typedef boost::shared_ptr < const Self > | ConstPtr |
typedef DerivedT | Derived |
typedef MeshTraitsT::EdgeData | EdgeData |
typedef pcl::PointCloud< EdgeData > | EdgeDataCloud |
typedef pcl::geometry::EdgeIndex | EdgeIndex |
typedef std::vector< EdgeIndex > | EdgeIndices |
typedef pcl::geometry::FaceAroundFaceCirculator < const Self > | FaceAroundFaceCirculator |
typedef pcl::geometry::FaceAroundVertexCirculator < const Self > | FaceAroundVertexCirculator |
typedef MeshTraitsT::FaceData | FaceData |
typedef pcl::PointCloud< FaceData > | FaceDataCloud |
typedef pcl::geometry::FaceIndex | FaceIndex |
typedef std::vector< FaceIndex > | FaceIndices |
typedef MeshTraitsT::HalfEdgeData | HalfEdgeData |
typedef pcl::PointCloud < HalfEdgeData > | HalfEdgeDataCloud |
typedef pcl::geometry::HalfEdgeIndex | HalfEdgeIndex |
typedef std::vector < HalfEdgeIndex > | HalfEdgeIndices |
typedef boost::integral_constant< bool,!boost::is_same < EdgeData, pcl::geometry::NoData >::value > | HasEdgeData |
typedef boost::integral_constant< bool,!boost::is_same < FaceData, pcl::geometry::NoData >::value > | HasFaceData |
typedef boost::integral_constant< bool,!boost::is_same < HalfEdgeData, pcl::geometry::NoData >::value > | HasHalfEdgeData |
typedef boost::integral_constant< bool,!boost::is_same < VertexData, pcl::geometry::NoData >::value > | HasVertexData |
typedef pcl::geometry::IncomingHalfEdgeAroundVertexCirculator < const Self > | IncomingHalfEdgeAroundVertexCirculator |
typedef pcl::geometry::InnerHalfEdgeAroundFaceCirculator < const Self > | InnerHalfEdgeAroundFaceCirculator |
typedef MeshTraitsT::IsManifold | IsManifold |
typedef MeshTagT | MeshTag |
typedef pcl::geometry::OuterHalfEdgeAroundFaceCirculator < const Self > | OuterHalfEdgeAroundFaceCirculator |
typedef pcl::geometry::OutgoingHalfEdgeAroundVertexCirculator < const Self > | OutgoingHalfEdgeAroundVertexCirculator |
typedef boost::shared_ptr< Self > | Ptr |
typedef MeshBase< DerivedT, MeshTraitsT, MeshTagT > | Self |
typedef pcl::geometry::VertexAroundFaceCirculator < const Self > | VertexAroundFaceCirculator |
typedef pcl::geometry::VertexAroundVertexCirculator < const Self > | VertexAroundVertexCirculator |
typedef MeshTraitsT::VertexData | VertexData |
typedef pcl::PointCloud < VertexData > | VertexDataCloud |
typedef pcl::geometry::VertexIndex | VertexIndex |
typedef std::vector< VertexIndex > | VertexIndices |
Public Member Functions | |
FaceIndex | addFace (const VertexIndices &vertices, const FaceData &face_data=FaceData(), const EdgeData &edge_data=EdgeData(), const HalfEdgeData &half_edge_data=HalfEdgeData()) |
Add a face to the mesh. Data is only added if it is associated with the elements. The last vertex is connected with the first one. | |
VertexIndex | addVertex (const VertexData &vertex_data=VertexData()) |
Add a vertex to the mesh. | |
BOOST_CONCEPT_ASSERT ((boost::Convertible< IsManifold, bool >)) | |
void | cleanUp () |
Removes all mesh elements and data that are marked as deleted. | |
void | clear () |
Clear all mesh elements and data. | |
void | deleteEdge (const HalfEdgeIndex &idx_he) |
Mark the given half-edge, the opposite half-edge and the associated faces as deleted. | |
void | deleteEdge (const EdgeIndex &idx_edge) |
Mark the given edge (both half-edges) and the associated faces as deleted. | |
void | deleteFace (const FaceIndex &idx_face) |
Mark the given face as deleted. More faces are deleted if the manifold mesh would become non-manifold. | |
void | deleteVertex (const VertexIndex &idx_vertex) |
Mark the given vertex and all connected half-edges and faces as deleted. | |
bool | empty () const |
Check if the mesh is empty. | |
bool | emptyEdges () const |
Check if the edges are empty. | |
bool | emptyFaces () const |
Check if the faces are empty. | |
bool | emptyVertices () const |
Check if the vertices are empty. | |
EdgeDataCloud & | getEdgeDataCloud () |
Get access to the stored edge data. | |
EdgeDataCloud | getEdgeDataCloud () const |
Get the stored edge data. | |
EdgeIndex | getEdgeIndex (const EdgeData &edge_data) const |
Get the index associated to the given edge data. | |
FaceAroundFaceCirculator | getFaceAroundFaceCirculator (const FaceIndex &idx_face) const |
FaceAroundFaceCirculator | getFaceAroundFaceCirculator (const HalfEdgeIndex &idx_inner_half_edge) const |
FaceAroundVertexCirculator | getFaceAroundVertexCirculator (const VertexIndex &idx_vertex) const |
FaceAroundVertexCirculator | getFaceAroundVertexCirculator (const HalfEdgeIndex &idx_outgoing_half_edge) const |
FaceDataCloud & | getFaceDataCloud () |
Get access to the stored face data. | |
FaceDataCloud | getFaceDataCloud () const |
Get the stored face data. | |
FaceIndex | getFaceIndex (const HalfEdgeIndex &idx_half_edge) const |
Get the face index to a given half-edge. | |
FaceIndex | getFaceIndex (const FaceData &face_data) const |
Get the index associated to the given face data. | |
HalfEdgeDataCloud & | getHalfEdgeDataCloud () |
Get access to the stored half-edge data. | |
HalfEdgeDataCloud | getHalfEdgeDataCloud () const |
Get the stored half-edge data. | |
HalfEdgeIndex | getHalfEdgeIndex (const HalfEdgeData &half_edge_data) const |
Get the index associated to the given half-edge data. | |
IncomingHalfEdgeAroundVertexCirculator | getIncomingHalfEdgeAroundVertexCirculator (const VertexIndex &idx_vertex) const |
IncomingHalfEdgeAroundVertexCirculator | getIncomingHalfEdgeAroundVertexCirculator (const HalfEdgeIndex &idx_incoming_half_edge) const |
HalfEdgeIndex | getIncomingHalfEdgeIndex (const VertexIndex &idx_vertex) const |
Get the incoming half-edge index to a given vertex. | |
InnerHalfEdgeAroundFaceCirculator | getInnerHalfEdgeAroundFaceCirculator (const FaceIndex &idx_face) const |
InnerHalfEdgeAroundFaceCirculator | getInnerHalfEdgeAroundFaceCirculator (const HalfEdgeIndex &idx_inner_half_edge) const |
HalfEdgeIndex | getInnerHalfEdgeIndex (const FaceIndex &idx_face) const |
Get the inner half-edge index to a given face. | |
HalfEdgeIndex | getNextHalfEdgeIndex (const HalfEdgeIndex &idx_half_edge) const |
Get the next half-edge index to a given half-edge. | |
FaceIndex | getOppositeFaceIndex (const HalfEdgeIndex &idx_half_edge) const |
Get the face index to a given half-edge. | |
HalfEdgeIndex | getOppositeHalfEdgeIndex (const HalfEdgeIndex &idx_half_edge) const |
Get the opposite half-edge index to a given half-edge. | |
VertexIndex | getOriginatingVertexIndex (const HalfEdgeIndex &idx_half_edge) const |
Get the originating vertex index to a given half-edge. | |
OuterHalfEdgeAroundFaceCirculator | getOuterHalfEdgeAroundFaceCirculator (const FaceIndex &idx_face) const |
OuterHalfEdgeAroundFaceCirculator | getOuterHalfEdgeAroundFaceCirculator (const HalfEdgeIndex &idx_inner_half_edge) const |
HalfEdgeIndex | getOuterHalfEdgeIndex (const FaceIndex &idx_face) const |
Get the outer half-edge inex to a given face. | |
OutgoingHalfEdgeAroundVertexCirculator | getOutgoingHalfEdgeAroundVertexCirculator (const VertexIndex &idx_vertex) const |
OutgoingHalfEdgeAroundVertexCirculator | getOutgoingHalfEdgeAroundVertexCirculator (const HalfEdgeIndex &idx_outgoing_half_edge) const |
HalfEdgeIndex | getOutgoingHalfEdgeIndex (const VertexIndex &idx_vertex) const |
Get the outgoing half-edge index to a given vertex. | |
HalfEdgeIndex | getPrevHalfEdgeIndex (const HalfEdgeIndex &idx_half_edge) const |
Get the previous half-edge index to a given half-edge. | |
VertexIndex | getTerminatingVertexIndex (const HalfEdgeIndex &idx_half_edge) const |
Get the terminating vertex index to a given half-edge. | |
VertexAroundFaceCirculator | getVertexAroundFaceCirculator (const FaceIndex &idx_face) const |
VertexAroundFaceCirculator | getVertexAroundFaceCirculator (const HalfEdgeIndex &idx_inner_half_edge) const |
VertexAroundVertexCirculator | getVertexAroundVertexCirculator (const VertexIndex &idx_vertex) const |
VertexAroundVertexCirculator | getVertexAroundVertexCirculator (const HalfEdgeIndex &idx_outgoing_half_edge) const |
VertexDataCloud & | getVertexDataCloud () |
Get access to the stored vertex data. | |
VertexDataCloud | getVertexDataCloud () const |
Get the stored vertex data. | |
VertexIndex | getVertexIndex (const VertexData &vertex_data) const |
Get the index associated to the given vertex data. | |
bool | isBoundary (const VertexIndex &idx_vertex) const |
Check if the given vertex lies on the boundary. Isolated vertices are considered to be on the boundary. | |
bool | isBoundary (const HalfEdgeIndex &idx_he) const |
Check if the given half-edge lies on the bounddary. | |
bool | isBoundary (const EdgeIndex &idx_edge) const |
Check if the given edge lies on the boundary (any of the two half-edges lies on the boundary. | |
template<bool CheckVerticesT> | |
bool | isBoundary (const FaceIndex &idx_face) const |
Check if the given face lies on the boundary. There are two versions of this method, selected by the template parameter. | |
bool | isBoundary (const FaceIndex &idx_face) const |
Check if the given face lies on the boundary. This method uses isBoundary <true> which checks if any vertex lies on the boundary. | |
bool | isDeleted (const VertexIndex &idx_vertex) const |
Check if the given vertex is marked as deleted. | |
bool | isDeleted (const HalfEdgeIndex &idx_he) const |
Check if the given half-edge is marked as deleted. | |
bool | isDeleted (const EdgeIndex &idx_edge) const |
Check if the given edge (any of the two half-edges) is marked as deleted. | |
bool | isDeleted (const FaceIndex &idx_face) const |
Check if the given face is marked as deleted. | |
bool | isEqualTopology (const Self &other) const |
Check if the other mesh has the same topology as this mesh. | |
bool | isIsolated (const VertexIndex &idx_vertex) const |
Check if the given vertex is isolated (not connected to other elements). | |
bool | isManifold (const VertexIndex &idx_vertex) const |
Check if the given vertex is manifold. Isolated vertices are manifold. | |
bool | isManifold () const |
Check if the mesh is manifold. | |
bool | isValid (const VertexIndex &idx_vertex) const |
Check if the given vertex index is a valid index into the mesh. | |
bool | isValid (const HalfEdgeIndex &idx_he) const |
Check if the given half-edge index is a valid index into the mesh. | |
bool | isValid (const EdgeIndex &idx_edge) const |
Check if the given edge index is a valid index into the mesh. | |
bool | isValid (const FaceIndex &idx_face) const |
Check if the given face index is a valid index into the mesh. | |
MeshBase () | |
Constructor. | |
void | reserveEdges (const size_t n) |
Reserve storage space for n edges (2*n storage space is reserved for the half-edges). | |
void | reserveFaces (const size_t n) |
Reserve storage space for n faces. | |
void | reserveVertices (const size_t n) |
Reserve storage space n vertices. | |
void | resizeEdges (const size_t n, const EdgeData &edge_data=EdgeData(), const HalfEdgeData he_data=HalfEdgeData()) |
Resize the edges to n elements (half-edges will hold 2*n elements). | |
void | resizeFaces (const size_t n, const FaceData &data=FaceData()) |
Resize the faces to n elements. | |
void | resizeVertices (const size_t n, const VertexData &data=VertexData()) |
Resize the the vertices to n elements. | |
bool | setEdgeDataCloud (const EdgeDataCloud &edge_data_cloud) |
Change the stored edge data. | |
bool | setFaceDataCloud (const FaceDataCloud &face_data_cloud) |
Change the stored face data. | |
bool | setHalfEdgeDataCloud (const HalfEdgeDataCloud &half_edge_data_cloud) |
Change the stored half-edge data. | |
bool | setVertexDataCloud (const VertexDataCloud &vertex_data_cloud) |
Change the stored vertex data. | |
size_t | sizeEdges () const |
Get the number of the edges. | |
size_t | sizeFaces () const |
Get the number of the faces. | |
size_t | sizeHalfEdges () const |
Get the number of the half-edges. | |
size_t | sizeVertices () const |
Get the number of the vertices. | |
Protected Types | |
typedef pcl::geometry::Face | Face |
typedef Faces::const_iterator | FaceConstIterator |
typedef Faces::iterator | FaceIterator |
typedef std::vector< Face > | Faces |
typedef pcl::geometry::HalfEdge | HalfEdge |
typedef HalfEdges::const_iterator | HalfEdgeConstIterator |
typedef HalfEdges::iterator | HalfEdgeIterator |
typedef std::vector< HalfEdge > | HalfEdges |
typedef pcl::geometry::Vertex | Vertex |
typedef Vertices::const_iterator | VertexConstIterator |
typedef Vertices::iterator | VertexIterator |
typedef std::vector< Vertex > | Vertices |
Protected Member Functions | |
template<class DataT > | |
void | addData (pcl::PointCloud< DataT > &cloud, const DataT &data, boost::true_type) |
Add mesh data. | |
template<class DataT > | |
void | addData (pcl::PointCloud< DataT > &, const DataT &, boost::false_type) |
Does nothing. | |
HalfEdgeIndex | addEdge (const VertexIndex &idx_v_a, const VertexIndex &idx_v_b, const HalfEdgeData &he_data, const EdgeData &edge_data) |
Add an edge between the two given vertices and connect them with the vertices. | |
FaceIndex | addFaceImplBase (const VertexIndices &vertices, const FaceData &face_data, const EdgeData &edge_data, const HalfEdgeData &half_edge_data) |
General implementation of addFace. | |
template<class ConstIteratorT , class IteratorT > | |
void | assignIf (const ConstIteratorT source, IteratorT target, boost::true_type) const |
Assign the source iterator to the target iterator. | |
template<class ConstIteratorT , class IteratorT > | |
void | assignIf (const ConstIteratorT, IteratorT, boost::false_type) const |
Does nothing. | |
bool | checkTopology1 (const VertexIndex &idx_v_a, const VertexIndex &idx_v_b, HalfEdgeIndex &idx_he_ab, std::vector< bool >::reference is_new_ab, boost::true_type) const |
Check if the edge between the two vertices can be added. | |
bool | checkTopology1 (const VertexIndex &idx_v_a, const VertexIndex &idx_v_b, HalfEdgeIndex &idx_he_ab, std::vector< bool >::reference is_new_ab, boost::false_type) const |
Non manifold version of checkTopology1. | |
bool | checkTopology2 (const HalfEdgeIndex &, const HalfEdgeIndex &, const bool is_new_ab, const bool is_new_bc, const bool is_isolated_b, std::vector< bool >::reference, HalfEdgeIndex &, boost::true_type) const |
Check if the face may be added (mesh does not become non-manifold). | |
bool | checkTopology2 (const HalfEdgeIndex &idx_he_ab, const HalfEdgeIndex &idx_he_bc, const bool is_new_ab, const bool is_new_bc, const bool, std::vector< bool >::reference make_adjacent_ab_bc, HalfEdgeIndex &idx_free_half_edge, boost::false_type) const |
Check if the half-edge bc is the next half-edge of ab. | |
template<class DataCloudT > | |
void | clearData (DataCloudT &cloud, boost::true_type) const |
Clear the mesh data. | |
template<class DataCloudT > | |
void | clearData (DataCloudT &, boost::false_type) const |
Does nothing. | |
FaceIndex | connectFace (const HalfEdgeIndices &inner_he, const FaceData &face_data) |
Add a face to the mesh and connect it to the half-edges. | |
void | connectNewNew (const HalfEdgeIndex &idx_he_ab, const HalfEdgeIndex &idx_he_bc, const VertexIndex &idx_v_b, boost::true_type) |
Both half-edges are new (manifold version). | |
void | connectNewNew (const HalfEdgeIndex &idx_he_ab, const HalfEdgeIndex &idx_he_bc, const VertexIndex &idx_v_b, boost::false_type) |
Both half-edges are new (non-manifold version). | |
void | connectNewOld (const HalfEdgeIndex &idx_he_ab, const HalfEdgeIndex &idx_he_bc, const VertexIndex &idx_v_b) |
The first half-edge is new. | |
void | connectOldNew (const HalfEdgeIndex &idx_he_ab, const HalfEdgeIndex &idx_he_bc, const VertexIndex &idx_v_b) |
The second half-edge is new. | |
void | connectOldOld (const HalfEdgeIndex &, const HalfEdgeIndex &, const VertexIndex &, boost::true_type) |
Both half-edges are old (manifold version). | |
void | connectOldOld (const HalfEdgeIndex &, const HalfEdgeIndex &idx_he_bc, const VertexIndex &idx_v_b, boost::false_type) |
Both half-edges are old (non-manifold version). | |
void | connectPrevNext (const HalfEdgeIndex &idx_he_ab, const HalfEdgeIndex &idx_he_bc) |
Connect the next and prev indices of the two half-edges with each other. | |
void | deleteFace (const FaceIndex &idx_face, boost::true_type) |
Manifold version of deleteFace. If the mesh becomes non-manifold due to the delete operation the faces around the non-manifold vertex are deleted until the mesh becomes manifold again. | |
void | deleteFace (const FaceIndex &idx_face, boost::false_type) |
Non-manifold version of deleteFace. | |
Face & | getFace (const FaceIndex &idx_face) |
Get the face for the given index. | |
Face | getFace (const FaceIndex &idx_face) const |
Get the face for the given index. | |
HalfEdge & | getHalfEdge (const HalfEdgeIndex &idx_he) |
Get the half-edge for the given index. | |
HalfEdge | getHalfEdge (const HalfEdgeIndex &idx_he) const |
Get the half-edge for the given index. | |
Vertex & | getVertex (const VertexIndex &idx_vertex) |
Get the vertex for the given index. | |
Vertex | getVertex (const VertexIndex &idx_vertex) const |
Get the vertex for the given index. | |
template<class IteratorT > | |
void | incrementIf (IteratorT &it, boost::true_type) const |
Increment the iterator. | |
template<class IteratorT > | |
void | incrementIf (IteratorT &, boost::false_type) const |
Does nothing. | |
bool | isBoundary (const FaceIndex &idx_face, boost::true_type) const |
Check if any vertex of the face lies on the boundary. | |
bool | isBoundary (const FaceIndex &idx_face, boost::false_type) const |
Check if any edge of the face lies on the boundary. | |
bool | isManifold (const VertexIndex &, boost::true_type) const |
Always manifold. | |
bool | isManifold (const VertexIndex &idx_vertex, boost::false_type) const |
Check if the given vertex is manifold. | |
bool | isManifold (boost::true_type) const |
Always manifold. | |
bool | isManifold (boost::false_type) const |
Check if all vertices in the mesh are manifold. | |
void | makeAdjacent (const HalfEdgeIndex &idx_he_ab, const HalfEdgeIndex &idx_he_bc, HalfEdgeIndex &idx_free_half_edge) |
Make the half-edges bc the next half-edge of ab. | |
void | markDeleted (const VertexIndex &idx_vertex) |
Mark the given vertex as deleted. | |
void | markDeleted (const HalfEdgeIndex &idx_he) |
Mark the given half-edge as deleted. | |
void | markDeleted (const EdgeIndex &idx_edge) |
Mark the given edge (both half-edges) as deleted. | |
void | markDeleted (const FaceIndex &idx_face) |
Mark the given face as deleted. | |
void | reconnect (const HalfEdgeIndex &idx_he_ab, const HalfEdgeIndex &idx_he_bc, const bool is_boundary_ba, const bool is_boundary_cb) |
Deconnect the input half-edges from the mesh and adjust the indices of the connected half-edges. | |
void | reconnectNBNB (const HalfEdgeIndex &idx_he_bc, const HalfEdgeIndex &idx_he_cb, const VertexIndex &idx_v_b, boost::true_type) |
Both edges are not on the boundary. Manifold version. | |
void | reconnectNBNB (const HalfEdgeIndex &idx_he_bc, const HalfEdgeIndex &, const VertexIndex &idx_v_b, boost::false_type) |
Both edges are not on the boundary. Non-manifold version. | |
template<class ElementContainerT , class DataContainerT , class IndexContainerT , class HasDataT > | |
IndexContainerT | remove (ElementContainerT &elements, DataContainerT &data_cloud) |
Removes mesh elements and data that are marked as deleted from the container. e.g. std::vector <VertexIndex> e.g. std::vector <Vertex> e.g. std::vector <VertexData> Integral constant specifying if the mesh has data associated with the elements. | |
template<class DataCloudT > | |
void | reserveData (DataCloudT &cloud, const size_t n, boost::true_type) const |
Reserve storage space for the mesh data. | |
template<class DataCloudT > | |
void | reserveData (DataCloudT &, const size_t, boost::false_type) const |
Does nothing. | |
template<class DataCloudT > | |
void | resizeData (DataCloudT &data_cloud, const size_t n, const typename DataCloudT::value_type &data, boost::true_type) const |
Resize the mesh data. | |
template<class DataCloudT > | |
void | resizeData (DataCloudT &, const size_t, const typename DataCloudT::value_type &, boost::false_type) const |
Does nothing. | |
void | setFace (const FaceIndex &idx_face, const Face &face) |
Set the face at the given index. | |
void | setFaceIndex (const HalfEdgeIndex &idx_half_edge, const FaceIndex &idx_face) |
Set the face index to a given half-edge. | |
void | setHalfEdge (const HalfEdgeIndex &idx_he, const HalfEdge &half_edge) |
Set the half-edge at the given index. | |
void | setInnerHalfEdgeIndex (const FaceIndex &idx_face, const HalfEdgeIndex &idx_inner_half_edge) |
Set the inner half-edge index to a given face. | |
void | setNextHalfEdgeIndex (const HalfEdgeIndex &idx_half_edge, const HalfEdgeIndex &idx_next_half_edge) |
Set the next half_edge index to a given half-edge. | |
void | setOutgoingHalfEdgeIndex (const VertexIndex &idx_vertex, const HalfEdgeIndex &idx_outgoing_half_edge) |
Set the outgoing half-edge index to a given vertex. | |
void | setPrevHalfEdgeIndex (const HalfEdgeIndex &idx_half_edge, const HalfEdgeIndex &idx_prev_half_edge) |
Set the previous half-edge index to a given half-edge. | |
void | setTerminatingVertexIndex (const HalfEdgeIndex &idx_half_edge, const VertexIndex &idx_terminating_vertex) |
Set the terminating vertex index to a given half-edge. | |
void | setVertex (const VertexIndex &idx_vertex, const Vertex &vertex) |
Set the vertex at the given index. | |
Private Attributes | |
FaceIndices | delete_faces_face_ |
Storage for deleteFace. | |
FaceIndices | delete_faces_vertex_ |
Storage for deleteVertex. | |
EdgeDataCloud | edge_data_cloud_ |
Data stored for the edges. | |
FaceDataCloud | face_data_cloud_ |
Data stored for the faces. | |
Faces | faces_ |
Connectivity information for the faces. | |
HalfEdgeIndices | free_he_ |
Storage for addFaceImplBase. | |
HalfEdgeDataCloud | half_edge_data_cloud_ |
Data stored for the half-edges. | |
HalfEdges | half_edges_ |
Connectivity information for the half-edges. | |
HalfEdgeIndices | inner_he_ |
Storage for addFaceImplBase and deleteFace. | |
std::vector< bool > | is_boundary_ |
Storage for deleteFace. | |
std::vector< bool > | is_new_ |
Storage for addFaceImplBase. | |
std::vector< bool > | make_adjacent_ |
Storage for addFaceImplBase. | |
VertexDataCloud | vertex_data_cloud_ |
Data stored for the vertices. | |
Vertices | vertices_ |
Connectivity information for the vertices. | |
Friends | |
class | pcl::geometry::MeshIO |
Base class for the half-edge mesh.
DerivedT | Has to implement the method 'addFaceImpl'. Please have a look at pcl::geometry::TriangleMesh, pcl::geometry::QuadMesh and pcl::geometry::PolygonMesh. |
MeshTraitsT | Please have a look at pcl::geometry::DefaultMeshTraits. |
MeshTagT | Tag describing the type of the mesh, e.g. TriangleMeshTag, QuadMeshTag, PolygonMeshTag. |
Definition at line 98 of file mesh_base.h.
typedef boost::shared_ptr<const Self> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::ConstPtr |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 104 of file mesh_base.h.
typedef DerivedT pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::Derived |
Definition at line 106 of file mesh_base.h.
typedef MeshTraitsT::EdgeData pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::EdgeData |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 111 of file mesh_base.h.
typedef pcl::PointCloud<EdgeData> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::EdgeDataCloud |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 128 of file mesh_base.h.
typedef pcl::geometry::EdgeIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::EdgeIndex |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 134 of file mesh_base.h.
typedef std::vector<EdgeIndex> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::EdgeIndices |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 139 of file mesh_base.h.
typedef pcl::geometry::Face pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::Face [protected] |
Definition at line 1128 of file mesh_base.h.
typedef pcl::geometry::FaceAroundFaceCirculator<const Self> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::FaceAroundFaceCirculator |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 150 of file mesh_base.h.
typedef pcl::geometry::FaceAroundVertexCirculator<const Self> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::FaceAroundVertexCirculator |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 146 of file mesh_base.h.
typedef Faces::const_iterator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::FaceConstIterator [protected] |
Definition at line 1140 of file mesh_base.h.
typedef MeshTraitsT::FaceData pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::FaceData |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 112 of file mesh_base.h.
typedef pcl::PointCloud<FaceData> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::FaceDataCloud |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 129 of file mesh_base.h.
typedef pcl::geometry::FaceIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::FaceIndex |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 135 of file mesh_base.h.
typedef std::vector<FaceIndex> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::FaceIndices |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 140 of file mesh_base.h.
typedef Faces::iterator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::FaceIterator [protected] |
Definition at line 1136 of file mesh_base.h.
typedef std::vector<Face> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::Faces [protected] |
Definition at line 1132 of file mesh_base.h.
typedef pcl::geometry::HalfEdge pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::HalfEdge [protected] |
Definition at line 1127 of file mesh_base.h.
typedef HalfEdges::const_iterator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::HalfEdgeConstIterator [protected] |
Definition at line 1139 of file mesh_base.h.
typedef MeshTraitsT::HalfEdgeData pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::HalfEdgeData |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 110 of file mesh_base.h.
typedef pcl::PointCloud<HalfEdgeData> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::HalfEdgeDataCloud |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 127 of file mesh_base.h.
typedef pcl::geometry::HalfEdgeIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::HalfEdgeIndex |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 133 of file mesh_base.h.
typedef std::vector<HalfEdgeIndex> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::HalfEdgeIndices |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 138 of file mesh_base.h.
typedef HalfEdges::iterator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::HalfEdgeIterator [protected] |
Definition at line 1135 of file mesh_base.h.
typedef std::vector<HalfEdge> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::HalfEdges [protected] |
Definition at line 1131 of file mesh_base.h.
typedef boost::integral_constant<bool, !boost::is_same <EdgeData , pcl::geometry::NoData>::value> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::HasEdgeData |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 123 of file mesh_base.h.
typedef boost::integral_constant<bool, !boost::is_same <FaceData , pcl::geometry::NoData>::value> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::HasFaceData |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 124 of file mesh_base.h.
typedef boost::integral_constant<bool, !boost::is_same <HalfEdgeData, pcl::geometry::NoData>::value> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::HasHalfEdgeData |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 122 of file mesh_base.h.
typedef boost::integral_constant<bool, !boost::is_same <VertexData , pcl::geometry::NoData>::value> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::HasVertexData |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 121 of file mesh_base.h.
typedef pcl::geometry::IncomingHalfEdgeAroundVertexCirculator<const Self> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::IncomingHalfEdgeAroundVertexCirculator |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 145 of file mesh_base.h.
typedef pcl::geometry::InnerHalfEdgeAroundFaceCirculator<const Self> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::InnerHalfEdgeAroundFaceCirculator |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 148 of file mesh_base.h.
typedef MeshTraitsT::IsManifold pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::IsManifold |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 113 of file mesh_base.h.
typedef MeshTagT pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::MeshTag |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 118 of file mesh_base.h.
typedef pcl::geometry::OuterHalfEdgeAroundFaceCirculator<const Self> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::OuterHalfEdgeAroundFaceCirculator |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 149 of file mesh_base.h.
typedef pcl::geometry::OutgoingHalfEdgeAroundVertexCirculator<const Self> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::OutgoingHalfEdgeAroundVertexCirculator |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 144 of file mesh_base.h.
typedef boost::shared_ptr<Self> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::Ptr |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 103 of file mesh_base.h.
typedef MeshBase<DerivedT, MeshTraitsT, MeshTagT> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::Self |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 102 of file mesh_base.h.
typedef pcl::geometry::Vertex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::Vertex [protected] |
Definition at line 1126 of file mesh_base.h.
typedef pcl::geometry::VertexAroundFaceCirculator<const Self> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::VertexAroundFaceCirculator |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 147 of file mesh_base.h.
typedef pcl::geometry::VertexAroundVertexCirculator<const Self> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::VertexAroundVertexCirculator |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 143 of file mesh_base.h.
typedef Vertices::const_iterator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::VertexConstIterator [protected] |
Definition at line 1138 of file mesh_base.h.
typedef MeshTraitsT::VertexData pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::VertexData |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 109 of file mesh_base.h.
typedef pcl::PointCloud<VertexData> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::VertexDataCloud |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 126 of file mesh_base.h.
typedef pcl::geometry::VertexIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::VertexIndex |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 132 of file mesh_base.h.
typedef std::vector<VertexIndex> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::VertexIndices |
Reimplemented in pcl::geometry::TriangleMesh< MeshTraitsT >, pcl::geometry::TriangleMesh< MeshTraits >, pcl::geometry::PolygonMesh< MeshTraitsT >, and pcl::geometry::QuadMesh< MeshTraitsT >.
Definition at line 137 of file mesh_base.h.
typedef Vertices::iterator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::VertexIterator [protected] |
Definition at line 1134 of file mesh_base.h.
typedef std::vector<Vertex> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::Vertices [protected] |
Definition at line 1130 of file mesh_base.h.
pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::MeshBase | ( | ) | [inline] |
Constructor.
Definition at line 153 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::addData | ( | pcl::PointCloud< DataT > & | cloud, |
const DataT & | data, | ||
boost::true_type | |||
) | [inline, protected] |
Add mesh data.
Definition at line 1520 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::addData | ( | pcl::PointCloud< DataT > & | , |
const DataT & | , | ||
boost::false_type | |||
) | [inline, protected] |
Does nothing.
Definition at line 1528 of file mesh_base.h.
HalfEdgeIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::addEdge | ( | const VertexIndex & | idx_v_a, |
const VertexIndex & | idx_v_b, | ||
const HalfEdgeData & | he_data, | ||
const EdgeData & | edge_data | ||
) | [inline, protected] |
Add an edge between the two given vertices and connect them with the vertices.
[in] | idx_v_a | The first vertex index |
[in] | idx_v_b | The second vertex index |
[in] | he_data | Data associated with the half-edges. This is only added if the mesh has data associated with the half-edges. |
[in] | edge_data | Data associated with the edge. This is only added if the mesh has data associated with the edges. |
Definition at line 1219 of file mesh_base.h.
FaceIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::addFace | ( | const VertexIndices & | vertices, |
const FaceData & | face_data = FaceData () , |
||
const EdgeData & | edge_data = EdgeData () , |
||
const HalfEdgeData & | half_edge_data = HalfEdgeData () |
||
) | [inline] |
Add a face to the mesh. Data is only added if it is associated with the elements. The last vertex is connected with the first one.
[in] | vertices | Indices to the vertices of the new face. |
[in] | face_data | Data that is set for the face. |
[in] | half_edge_data | Data that is set for all added half-edges. |
[in] | edge_data | Data that is set for all added edges. |
Definition at line 196 of file mesh_base.h.
FaceIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::addFaceImplBase | ( | const VertexIndices & | vertices, |
const FaceData & | face_data, | ||
const EdgeData & | edge_data, | ||
const HalfEdgeData & | half_edge_data | ||
) | [inline, protected] |
General implementation of addFace.
Definition at line 1144 of file mesh_base.h.
VertexIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::addVertex | ( | const VertexData & | vertex_data = VertexData () | ) | [inline] |
Add a vertex to the mesh.
[in] | vertex_data | Data that is stored in the vertex. This is only added if the mesh has data associated with the vertices. |
Definition at line 180 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::assignIf | ( | const ConstIteratorT | source, |
IteratorT | target, | ||
boost::true_type | |||
) | const [inline, protected] |
Assign the source iterator to the target iterator.
Definition at line 1822 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::assignIf | ( | const ConstIteratorT | , |
IteratorT | , | ||
boost::false_type | |||
) | const [inline, protected] |
Does nothing.
Definition at line 1829 of file mesh_base.h.
pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::BOOST_CONCEPT_ASSERT | ( | (boost::Convertible< IsManifold, bool >) | ) |
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::checkTopology1 | ( | const VertexIndex & | idx_v_a, |
const VertexIndex & | idx_v_b, | ||
HalfEdgeIndex & | idx_he_ab, | ||
std::vector< bool >::reference | is_new_ab, | ||
boost::true_type | |||
) | const [inline, protected] |
Check if the edge between the two vertices can be added.
[in] | idx_v_a | Index to the first vertex. |
[in] | idx_v_b | Index to the second vertex. |
[out] | idx_he_ab | Index to the half-edge ab if is_new_ab=false. |
[out] | is_new_ab | true if the edge between the vertices exists already. Must be initialized with true! |
Definition at line 1246 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::checkTopology1 | ( | const VertexIndex & | idx_v_a, |
const VertexIndex & | idx_v_b, | ||
HalfEdgeIndex & | idx_he_ab, | ||
std::vector< bool >::reference | is_new_ab, | ||
boost::false_type | |||
) | const [inline, protected] |
Non manifold version of checkTopology1.
Definition at line 1264 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::checkTopology2 | ( | const HalfEdgeIndex & | , |
const HalfEdgeIndex & | , | ||
const bool | is_new_ab, | ||
const bool | is_new_bc, | ||
const bool | is_isolated_b, | ||
std::vector< bool >::reference | , | ||
HalfEdgeIndex & | , | ||
boost::true_type | |||
) | const [inline, protected] |
Check if the face may be added (mesh does not become non-manifold).
Definition at line 1294 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::checkTopology2 | ( | const HalfEdgeIndex & | idx_he_ab, |
const HalfEdgeIndex & | idx_he_bc, | ||
const bool | is_new_ab, | ||
const bool | is_new_bc, | ||
const bool | , | ||
std::vector< bool >::reference | make_adjacent_ab_bc, | ||
HalfEdgeIndex & | idx_free_half_edge, | ||
boost::false_type | |||
) | const [inline, protected] |
Check if the half-edge bc is the next half-edge of ab.
[in] | idx_he_ab | Index to the half-edge between the vertices a and b. |
[in] | idx_ha_bc | Index to the half-edge between the vertices b and c. |
[in] | is_new_ab | Half-edge ab is new. |
[in] | is_new_bc | Half-edge bc is new. |
[out] | make_adjacent_ab_bc | Half-edges ab and bc need to be made adjacent. |
[out] | idx_free_half_edge | Free half-edge (needed for makeAdjacent) |
Definition at line 1317 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::cleanUp | ( | ) | [inline] |
Removes all mesh elements and data that are marked as deleted.
Definition at line 275 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::clear | ( | ) | [inline] |
Clear all mesh elements and data.
Definition at line 889 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::clearData | ( | DataCloudT & | cloud, |
boost::true_type | |||
) | const [inline, protected] |
Clear the mesh data.
Definition at line 1999 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::clearData | ( | DataCloudT & | , |
boost::false_type | |||
) | const [inline, protected] |
Does nothing.
Definition at line 2006 of file mesh_base.h.
FaceIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::connectFace | ( | const HalfEdgeIndices & | inner_he, |
const FaceData & | face_data | ||
) | [inline, protected] |
Add a face to the mesh and connect it to the half-edges.
[in] | inner_he | Inner half-edges of the face. |
[in] | face_data | Data that is stored in the face. This is only added if the mesh has data associated with the faces. |
Definition at line 1381 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::connectNewNew | ( | const HalfEdgeIndex & | idx_he_ab, |
const HalfEdgeIndex & | idx_he_bc, | ||
const VertexIndex & | idx_v_b, | ||
boost::true_type | |||
) | [inline, protected] |
Both half-edges are new (manifold version).
Definition at line 1408 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::connectNewNew | ( | const HalfEdgeIndex & | idx_he_ab, |
const HalfEdgeIndex & | idx_he_bc, | ||
const VertexIndex & | idx_v_b, | ||
boost::false_type | |||
) | [inline, protected] |
Both half-edges are new (non-manifold version).
Definition at line 1424 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::connectNewOld | ( | const HalfEdgeIndex & | idx_he_ab, |
const HalfEdgeIndex & | idx_he_bc, | ||
const VertexIndex & | idx_v_b | ||
) | [inline, protected] |
The first half-edge is new.
Definition at line 1450 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::connectOldNew | ( | const HalfEdgeIndex & | idx_he_ab, |
const HalfEdgeIndex & | idx_he_bc, | ||
const VertexIndex & | idx_v_b | ||
) | [inline, protected] |
The second half-edge is new.
Definition at line 1465 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::connectOldOld | ( | const HalfEdgeIndex & | , |
const HalfEdgeIndex & | , | ||
const VertexIndex & | , | ||
boost::true_type | |||
) | [inline, protected] |
Both half-edges are old (manifold version).
Definition at line 1480 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::connectOldOld | ( | const HalfEdgeIndex & | , |
const HalfEdgeIndex & | idx_he_bc, | ||
const VertexIndex & | idx_v_b, | ||
boost::false_type | |||
) | [inline, protected] |
Both half-edges are old (non-manifold version).
Definition at line 1489 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::connectPrevNext | ( | const HalfEdgeIndex & | idx_he_ab, |
const HalfEdgeIndex & | idx_he_bc | ||
) | [inline, protected] |
Connect the next and prev indices of the two half-edges with each other.
Definition at line 1399 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::deleteEdge | ( | const HalfEdgeIndex & | idx_he | ) | [inline] |
Mark the given half-edge, the opposite half-edge and the associated faces as deleted.
Definition at line 235 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::deleteEdge | ( | const EdgeIndex & | idx_edge | ) | [inline] |
Mark the given edge (both half-edges) and the associated faces as deleted.
Definition at line 252 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::deleteFace | ( | const FaceIndex & | idx_face | ) | [inline] |
Mark the given face as deleted. More faces are deleted if the manifold mesh would become non-manifold.
Definition at line 263 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::deleteFace | ( | const FaceIndex & | idx_face, |
boost::true_type | |||
) | [inline, protected] |
Manifold version of deleteFace. If the mesh becomes non-manifold due to the delete operation the faces around the non-manifold vertex are deleted until the mesh becomes manifold again.
Definition at line 1538 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::deleteFace | ( | const FaceIndex & | idx_face, |
boost::false_type | |||
) | [inline, protected] |
Non-manifold version of deleteFace.
Definition at line 1557 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::deleteVertex | ( | const VertexIndex & | idx_vertex | ) | [inline] |
Mark the given vertex and all connected half-edges and faces as deleted.
Definition at line 209 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::empty | ( | ) | const [inline] |
Check if the mesh is empty.
Definition at line 797 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::emptyEdges | ( | ) | const [inline] |
Check if the edges are empty.
Definition at line 811 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::emptyFaces | ( | ) | const [inline] |
Check if the faces are empty.
Definition at line 818 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::emptyVertices | ( | ) | const [inline] |
Check if the vertices are empty.
Definition at line 804 of file mesh_base.h.
EdgeDataCloud& pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getEdgeDataCloud | ( | ) | [inline] |
Get access to the stored edge data.
Definition at line 985 of file mesh_base.h.
EdgeDataCloud pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getEdgeDataCloud | ( | ) | const [inline] |
Get the stored edge data.
Definition at line 992 of file mesh_base.h.
EdgeIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getEdgeIndex | ( | const EdgeData & | edge_data | ) | const [inline] |
Get the index associated to the given edge data.
Definition at line 1091 of file mesh_base.h.
Face& pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getFace | ( | const FaceIndex & | idx_face | ) | [inline, protected] |
Get the face for the given index.
Definition at line 2072 of file mesh_base.h.
Face pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getFace | ( | const FaceIndex & | idx_face | ) | const [inline, protected] |
Get the face for the given index.
Definition at line 2080 of file mesh_base.h.
FaceAroundFaceCirculator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getFaceAroundFaceCirculator | ( | const FaceIndex & | idx_face | ) | const [inline] |
Definition at line 552 of file mesh_base.h.
FaceAroundFaceCirculator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getFaceAroundFaceCirculator | ( | const HalfEdgeIndex & | idx_inner_half_edge | ) | const [inline] |
Definition at line 560 of file mesh_base.h.
FaceAroundVertexCirculator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getFaceAroundVertexCirculator | ( | const VertexIndex & | idx_vertex | ) | const [inline] |
Definition at line 488 of file mesh_base.h.
FaceAroundVertexCirculator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getFaceAroundVertexCirculator | ( | const HalfEdgeIndex & | idx_outgoing_half_edge | ) | const [inline] |
Definition at line 496 of file mesh_base.h.
FaceDataCloud& pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getFaceDataCloud | ( | ) | [inline] |
Get access to the stored face data.
Definition at line 1023 of file mesh_base.h.
FaceDataCloud pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getFaceDataCloud | ( | ) | const [inline] |
Get the stored face data.
Definition at line 1030 of file mesh_base.h.
FaceIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getFaceIndex | ( | const HalfEdgeIndex & | idx_half_edge | ) | const [inline] |
Get the face index to a given half-edge.
Definition at line 400 of file mesh_base.h.
FaceIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getFaceIndex | ( | const FaceData & | face_data | ) | const [inline] |
Get the index associated to the given face data.
Definition at line 1106 of file mesh_base.h.
HalfEdge& pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getHalfEdge | ( | const HalfEdgeIndex & | idx_he | ) | [inline, protected] |
Get the half-edge for the given index.
Definition at line 2044 of file mesh_base.h.
HalfEdge pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getHalfEdge | ( | const HalfEdgeIndex & | idx_he | ) | const [inline, protected] |
Get the half-edge for the given index.
Definition at line 2052 of file mesh_base.h.
HalfEdgeDataCloud& pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getHalfEdgeDataCloud | ( | ) | [inline] |
Get access to the stored half-edge data.
Definition at line 947 of file mesh_base.h.
HalfEdgeDataCloud pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getHalfEdgeDataCloud | ( | ) | const [inline] |
Get the stored half-edge data.
Definition at line 954 of file mesh_base.h.
HalfEdgeIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getHalfEdgeIndex | ( | const HalfEdgeData & | half_edge_data | ) | const [inline] |
Get the index associated to the given half-edge data.
Definition at line 1076 of file mesh_base.h.
IncomingHalfEdgeAroundVertexCirculator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getIncomingHalfEdgeAroundVertexCirculator | ( | const VertexIndex & | idx_vertex | ) | const [inline] |
Definition at line 472 of file mesh_base.h.
IncomingHalfEdgeAroundVertexCirculator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getIncomingHalfEdgeAroundVertexCirculator | ( | const HalfEdgeIndex & | idx_incoming_half_edge | ) | const [inline] |
Definition at line 480 of file mesh_base.h.
HalfEdgeIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getIncomingHalfEdgeIndex | ( | const VertexIndex & | idx_vertex | ) | const [inline] |
Get the incoming half-edge index to a given vertex.
Definition at line 347 of file mesh_base.h.
InnerHalfEdgeAroundFaceCirculator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getInnerHalfEdgeAroundFaceCirculator | ( | const FaceIndex & | idx_face | ) | const [inline] |
Definition at line 520 of file mesh_base.h.
InnerHalfEdgeAroundFaceCirculator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getInnerHalfEdgeAroundFaceCirculator | ( | const HalfEdgeIndex & | idx_inner_half_edge | ) | const [inline] |
Definition at line 528 of file mesh_base.h.
HalfEdgeIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getInnerHalfEdgeIndex | ( | const FaceIndex & | idx_face | ) | const [inline] |
Get the inner half-edge index to a given face.
Definition at line 420 of file mesh_base.h.
HalfEdgeIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getNextHalfEdgeIndex | ( | const HalfEdgeIndex & | idx_half_edge | ) | const [inline] |
Get the next half-edge index to a given half-edge.
Definition at line 384 of file mesh_base.h.
FaceIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getOppositeFaceIndex | ( | const HalfEdgeIndex & | idx_half_edge | ) | const [inline] |
Get the face index to a given half-edge.
Definition at line 408 of file mesh_base.h.
HalfEdgeIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getOppositeHalfEdgeIndex | ( | const HalfEdgeIndex & | idx_half_edge | ) | const [inline] |
Get the opposite half-edge index to a given half-edge.
Definition at line 375 of file mesh_base.h.
VertexIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getOriginatingVertexIndex | ( | const HalfEdgeIndex & | idx_half_edge | ) | const [inline] |
Get the originating vertex index to a given half-edge.
Definition at line 367 of file mesh_base.h.
OuterHalfEdgeAroundFaceCirculator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getOuterHalfEdgeAroundFaceCirculator | ( | const FaceIndex & | idx_face | ) | const [inline] |
Definition at line 536 of file mesh_base.h.
OuterHalfEdgeAroundFaceCirculator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getOuterHalfEdgeAroundFaceCirculator | ( | const HalfEdgeIndex & | idx_inner_half_edge | ) | const [inline] |
Definition at line 544 of file mesh_base.h.
HalfEdgeIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getOuterHalfEdgeIndex | ( | const FaceIndex & | idx_face | ) | const [inline] |
Get the outer half-edge inex to a given face.
Definition at line 428 of file mesh_base.h.
OutgoingHalfEdgeAroundVertexCirculator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getOutgoingHalfEdgeAroundVertexCirculator | ( | const VertexIndex & | idx_vertex | ) | const [inline] |
Definition at line 456 of file mesh_base.h.
OutgoingHalfEdgeAroundVertexCirculator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getOutgoingHalfEdgeAroundVertexCirculator | ( | const HalfEdgeIndex & | idx_outgoing_half_edge | ) | const [inline] |
Definition at line 464 of file mesh_base.h.
HalfEdgeIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getOutgoingHalfEdgeIndex | ( | const VertexIndex & | idx_vertex | ) | const [inline] |
Get the outgoing half-edge index to a given vertex.
Definition at line 339 of file mesh_base.h.
HalfEdgeIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getPrevHalfEdgeIndex | ( | const HalfEdgeIndex & | idx_half_edge | ) | const [inline] |
Get the previous half-edge index to a given half-edge.
Definition at line 392 of file mesh_base.h.
VertexIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getTerminatingVertexIndex | ( | const HalfEdgeIndex & | idx_half_edge | ) | const [inline] |
Get the terminating vertex index to a given half-edge.
Definition at line 359 of file mesh_base.h.
Vertex& pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getVertex | ( | const VertexIndex & | idx_vertex | ) | [inline, protected] |
Get the vertex for the given index.
Definition at line 2016 of file mesh_base.h.
Vertex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getVertex | ( | const VertexIndex & | idx_vertex | ) | const [inline, protected] |
Get the vertex for the given index.
Definition at line 2024 of file mesh_base.h.
VertexAroundFaceCirculator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getVertexAroundFaceCirculator | ( | const FaceIndex & | idx_face | ) | const [inline] |
Definition at line 504 of file mesh_base.h.
VertexAroundFaceCirculator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getVertexAroundFaceCirculator | ( | const HalfEdgeIndex & | idx_inner_half_edge | ) | const [inline] |
Definition at line 512 of file mesh_base.h.
VertexAroundVertexCirculator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getVertexAroundVertexCirculator | ( | const VertexIndex & | idx_vertex | ) | const [inline] |
Definition at line 440 of file mesh_base.h.
VertexAroundVertexCirculator pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getVertexAroundVertexCirculator | ( | const HalfEdgeIndex & | idx_outgoing_half_edge | ) | const [inline] |
Definition at line 448 of file mesh_base.h.
VertexDataCloud& pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getVertexDataCloud | ( | ) | [inline] |
Get access to the stored vertex data.
Definition at line 909 of file mesh_base.h.
VertexDataCloud pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getVertexDataCloud | ( | ) | const [inline] |
Get the stored vertex data.
Definition at line 916 of file mesh_base.h.
VertexIndex pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::getVertexIndex | ( | const VertexData & | vertex_data | ) | const [inline] |
Get the index associated to the given vertex data.
Definition at line 1061 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::incrementIf | ( | IteratorT & | it, |
boost::true_type | |||
) | const [inline, protected] |
Increment the iterator.
Definition at line 1809 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::incrementIf | ( | IteratorT & | , |
boost::false_type | |||
) | const [inline, protected] |
Does nothing.
Definition at line 1816 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isBoundary | ( | const VertexIndex & | idx_vertex | ) | const [inline] |
Check if the given vertex lies on the boundary. Isolated vertices are considered to be on the boundary.
Definition at line 695 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isBoundary | ( | const HalfEdgeIndex & | idx_he | ) | const [inline] |
Check if the given half-edge lies on the bounddary.
Definition at line 704 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isBoundary | ( | const EdgeIndex & | idx_edge | ) | const [inline] |
Check if the given edge lies on the boundary (any of the two half-edges lies on the boundary.
Definition at line 712 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isBoundary | ( | const FaceIndex & | idx_face | ) | const [inline] |
Check if the given face lies on the boundary. There are two versions of this method, selected by the template parameter.
CheckVerticesT | Check if any vertex lies on the boundary (true) or check if any edge lies on the boundary (false). |
Definition at line 723 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isBoundary | ( | const FaceIndex & | idx_face | ) | const [inline] |
Check if the given face lies on the boundary. This method uses isBoundary <true> which checks if any vertex lies on the boundary.
Definition at line 731 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isBoundary | ( | const FaceIndex & | idx_face, |
boost::true_type | |||
) | const [inline, protected] |
Check if any vertex of the face lies on the boundary.
Definition at line 1892 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isBoundary | ( | const FaceIndex & | idx_face, |
boost::false_type | |||
) | const [inline, protected] |
Check if any edge of the face lies on the boundary.
Definition at line 1910 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isDeleted | ( | const VertexIndex & | idx_vertex | ) | const [inline] |
Check if the given vertex is marked as deleted.
Definition at line 646 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isDeleted | ( | const HalfEdgeIndex & | idx_he | ) | const [inline] |
Check if the given half-edge is marked as deleted.
Definition at line 654 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isDeleted | ( | const EdgeIndex & | idx_edge | ) | const [inline] |
Check if the given edge (any of the two half-edges) is marked as deleted.
Definition at line 662 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isDeleted | ( | const FaceIndex & | idx_face | ) | const [inline] |
Check if the given face is marked as deleted.
Definition at line 671 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isEqualTopology | ( | const Self & | other | ) | const [inline] |
Check if the other mesh has the same topology as this mesh.
Definition at line 572 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isIsolated | ( | const VertexIndex & | idx_vertex | ) | const [inline] |
Check if the given vertex is isolated (not connected to other elements).
Definition at line 683 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isManifold | ( | const VertexIndex & | idx_vertex | ) | const [inline] |
Check if the given vertex is manifold. Isolated vertices are manifold.
Definition at line 743 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isManifold | ( | ) | const [inline] |
Check if the mesh is manifold.
Definition at line 752 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isManifold | ( | const VertexIndex & | , |
boost::true_type | |||
) | const [inline, protected] |
Always manifold.
Definition at line 1928 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isManifold | ( | const VertexIndex & | idx_vertex, |
boost::false_type | |||
) | const [inline, protected] |
Check if the given vertex is manifold.
Definition at line 1935 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isManifold | ( | boost::true_type | ) | const [inline, protected] |
Always manifold.
Definition at line 1951 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isManifold | ( | boost::false_type | ) | const [inline, protected] |
Check if all vertices in the mesh are manifold.
Definition at line 1958 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isValid | ( | const VertexIndex & | idx_vertex | ) | const [inline] |
Check if the given vertex index is a valid index into the mesh.
Definition at line 614 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isValid | ( | const HalfEdgeIndex & | idx_he | ) | const [inline] |
Check if the given half-edge index is a valid index into the mesh.
Definition at line 621 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isValid | ( | const EdgeIndex & | idx_edge | ) | const [inline] |
Check if the given edge index is a valid index into the mesh.
Definition at line 628 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::isValid | ( | const FaceIndex & | idx_face | ) | const [inline] |
Check if the given face index is a valid index into the mesh.
Definition at line 635 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::makeAdjacent | ( | const HalfEdgeIndex & | idx_he_ab, |
const HalfEdgeIndex & | idx_he_bc, | ||
HalfEdgeIndex & | idx_free_half_edge | ||
) | [inline, protected] |
Make the half-edges bc the next half-edge of ab.
[in] | idx_he_ab | Index to the half-edge between the vertices a and b. |
[in] | idx_ha_bc | Index to the half-edge between the vertices b and c. |
[in,out] | idx_free_half_edge | Free half-edge needed to re-connect the half-edges around vertex b. |
Definition at line 1357 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::markDeleted | ( | const VertexIndex & | idx_vertex | ) | [inline, protected] |
Mark the given vertex as deleted.
Definition at line 1710 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::markDeleted | ( | const HalfEdgeIndex & | idx_he | ) | [inline, protected] |
Mark the given half-edge as deleted.
Definition at line 1718 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::markDeleted | ( | const EdgeIndex & | idx_edge | ) | [inline, protected] |
Mark the given edge (both half-edges) as deleted.
Definition at line 1726 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::markDeleted | ( | const FaceIndex & | idx_face | ) | [inline, protected] |
Mark the given face as deleted.
Definition at line 1735 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::reconnect | ( | const HalfEdgeIndex & | idx_he_ab, |
const HalfEdgeIndex & | idx_he_bc, | ||
const bool | is_boundary_ba, | ||
const bool | is_boundary_cb | ||
) | [inline, protected] |
Deconnect the input half-edges from the mesh and adjust the indices of the connected half-edges.
Definition at line 1609 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::reconnectNBNB | ( | const HalfEdgeIndex & | idx_he_bc, |
const HalfEdgeIndex & | idx_he_cb, | ||
const VertexIndex & | idx_v_b, | ||
boost::true_type | |||
) | [inline, protected] |
Both edges are not on the boundary. Manifold version.
Definition at line 1657 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::reconnectNBNB | ( | const HalfEdgeIndex & | idx_he_bc, |
const HalfEdgeIndex & | , | ||
const VertexIndex & | idx_v_b, | ||
boost::false_type | |||
) | [inline, protected] |
Both edges are not on the boundary. Non-manifold version.
Definition at line 1693 of file mesh_base.h.
IndexContainerT pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::remove | ( | ElementContainerT & | elements, |
DataContainerT & | data_cloud | ||
) | [inline, protected] |
Removes mesh elements and data that are marked as deleted from the container. e.g. std::vector <VertexIndex> e.g. std::vector <Vertex> e.g. std::vector <VertexData> Integral constant specifying if the mesh has data associated with the elements.
[in,out] | elements | Container for the mesh elements. Resized to the new size. |
[in,out] | data_cloud | Container for the mesh data. Resized to the new size. |
Definition at line 1755 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::reserveData | ( | DataCloudT & | cloud, |
const size_t | n, | ||
boost::true_type | |||
) | const [inline, protected] |
Reserve storage space for the mesh data.
Definition at line 1973 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::reserveData | ( | DataCloudT & | , |
const size_t | , | ||
boost::false_type | |||
) | const [inline, protected] |
Does nothing.
Definition at line 1980 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::reserveEdges | ( | const size_t | n | ) | [inline] |
Reserve storage space for n edges (2*n storage space is reserved for the half-edges).
Definition at line 837 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::reserveFaces | ( | const size_t | n | ) | [inline] |
Reserve storage space for n faces.
Definition at line 846 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::reserveVertices | ( | const size_t | n | ) | [inline] |
Reserve storage space n vertices.
Definition at line 829 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::resizeData | ( | DataCloudT & | data_cloud, |
const size_t | n, | ||
const typename DataCloudT::value_type & | data, | ||
boost::true_type | |||
) | const [inline, protected] |
Resize the mesh data.
Definition at line 1986 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::resizeData | ( | DataCloudT & | , |
const size_t | , | ||
const typename DataCloudT::value_type & | , | ||
boost::false_type | |||
) | const [inline, protected] |
Does nothing.
Definition at line 1993 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::resizeEdges | ( | const size_t | n, |
const EdgeData & | edge_data = EdgeData () , |
||
const HalfEdgeData | he_data = HalfEdgeData () |
||
) | [inline] |
Resize the edges to n elements (half-edges will hold 2*n elements).
Definition at line 866 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::resizeFaces | ( | const size_t | n, |
const FaceData & | data = FaceData () |
||
) | [inline] |
Resize the faces to n elements.
Definition at line 877 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::resizeVertices | ( | const size_t | n, |
const VertexData & | data = VertexData () |
||
) | [inline] |
Resize the the vertices to n elements.
Definition at line 858 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::setEdgeDataCloud | ( | const EdgeDataCloud & | edge_data_cloud | ) | [inline] |
Change the stored edge data.
[in] | edge_data_cloud | The new edge data. Must be the same as the current data. |
Definition at line 1002 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::setFace | ( | const FaceIndex & | idx_face, |
const Face & | face | ||
) | [inline, protected] |
Set the face at the given index.
Definition at line 2088 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::setFaceDataCloud | ( | const FaceDataCloud & | face_data_cloud | ) | [inline] |
Change the stored face data.
[in] | face_data_cloud | The new face data. Must be the same as the current data. |
Definition at line 1040 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::setFaceIndex | ( | const HalfEdgeIndex & | idx_half_edge, |
const FaceIndex & | idx_face | ||
) | [inline, protected] |
Set the face index to a given half-edge.
Definition at line 1872 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::setHalfEdge | ( | const HalfEdgeIndex & | idx_he, |
const HalfEdge & | half_edge | ||
) | [inline, protected] |
Set the half-edge at the given index.
Definition at line 2060 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::setHalfEdgeDataCloud | ( | const HalfEdgeDataCloud & | half_edge_data_cloud | ) | [inline] |
Change the stored half-edge data.
[in] | half_edge_data_cloud | The new half-edge data. Must be the same as the current data. |
Definition at line 964 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::setInnerHalfEdgeIndex | ( | const FaceIndex & | idx_face, |
const HalfEdgeIndex & | idx_inner_half_edge | ||
) | [inline, protected] |
Set the inner half-edge index to a given face.
Definition at line 1880 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::setNextHalfEdgeIndex | ( | const HalfEdgeIndex & | idx_half_edge, |
const HalfEdgeIndex & | idx_next_half_edge | ||
) | [inline, protected] |
Set the next half_edge index to a given half-edge.
Definition at line 1855 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::setOutgoingHalfEdgeIndex | ( | const VertexIndex & | idx_vertex, |
const HalfEdgeIndex & | idx_outgoing_half_edge | ||
) | [inline, protected] |
Set the outgoing half-edge index to a given vertex.
Definition at line 1839 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::setPrevHalfEdgeIndex | ( | const HalfEdgeIndex & | idx_half_edge, |
const HalfEdgeIndex & | idx_prev_half_edge | ||
) | [inline, protected] |
Set the previous half-edge index to a given half-edge.
Definition at line 1863 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::setTerminatingVertexIndex | ( | const HalfEdgeIndex & | idx_half_edge, |
const VertexIndex & | idx_terminating_vertex | ||
) | [inline, protected] |
Set the terminating vertex index to a given half-edge.
Definition at line 1847 of file mesh_base.h.
void pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::setVertex | ( | const VertexIndex & | idx_vertex, |
const Vertex & | vertex | ||
) | [inline, protected] |
Set the vertex at the given index.
Definition at line 2032 of file mesh_base.h.
bool pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::setVertexDataCloud | ( | const VertexDataCloud & | vertex_data_cloud | ) | [inline] |
Change the stored vertex data.
[in] | vertex_data_cloud | The new vertex data. Must be the same as the current data. |
Definition at line 926 of file mesh_base.h.
size_t pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::sizeEdges | ( | ) | const [inline] |
Get the number of the edges.
Definition at line 778 of file mesh_base.h.
size_t pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::sizeFaces | ( | ) | const [inline] |
Get the number of the faces.
Definition at line 786 of file mesh_base.h.
size_t pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::sizeHalfEdges | ( | ) | const [inline] |
Get the number of the half-edges.
Definition at line 770 of file mesh_base.h.
size_t pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::sizeVertices | ( | ) | const [inline] |
Get the number of the vertices.
Definition at line 763 of file mesh_base.h.
friend class pcl::geometry::MeshIO [friend] |
Definition at line 2147 of file mesh_base.h.
FaceIndices pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::delete_faces_face_ [private] |
Storage for deleteFace.
Definition at line 2142 of file mesh_base.h.
FaceIndices pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::delete_faces_vertex_ [private] |
Storage for deleteVertex.
Definition at line 2139 of file mesh_base.h.
EdgeDataCloud pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::edge_data_cloud_ [private] |
Data stored for the edges.
Definition at line 2107 of file mesh_base.h.
FaceDataCloud pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::face_data_cloud_ [private] |
Data stored for the faces.
Definition at line 2110 of file mesh_base.h.
Faces pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::faces_ [private] |
Connectivity information for the faces.
Definition at line 2119 of file mesh_base.h.
HalfEdgeIndices pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::free_he_ [private] |
Storage for addFaceImplBase.
Definition at line 2127 of file mesh_base.h.
HalfEdgeDataCloud pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::half_edge_data_cloud_ [private] |
Data stored for the half-edges.
Definition at line 2104 of file mesh_base.h.
HalfEdges pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::half_edges_ [private] |
Connectivity information for the half-edges.
Definition at line 2116 of file mesh_base.h.
HalfEdgeIndices pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::inner_he_ [private] |
Storage for addFaceImplBase and deleteFace.
Definition at line 2124 of file mesh_base.h.
std::vector<bool> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::is_boundary_ [private] |
Storage for deleteFace.
Definition at line 2136 of file mesh_base.h.
std::vector<bool> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::is_new_ [private] |
Storage for addFaceImplBase.
Definition at line 2130 of file mesh_base.h.
std::vector<bool> pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::make_adjacent_ [private] |
Storage for addFaceImplBase.
Definition at line 2133 of file mesh_base.h.
VertexDataCloud pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::vertex_data_cloud_ [private] |
Data stored for the vertices.
Definition at line 2101 of file mesh_base.h.
Vertices pcl::geometry::MeshBase< DerivedT, MeshTraitsT, MeshTagT >::vertices_ [private] |
Connectivity information for the vertices.
Definition at line 2113 of file mesh_base.h.