Classes | |
struct | DefaultMeshTraits |
The mesh traits are used to set up compile time settings for the mesh. More... | |
class | EdgeIndex |
Index used to access elements in the half-edge mesh. It is basically just a wrapper around an integer with a few added methods. More... | |
class | Face |
A face is a closed loop of edges. More... | |
class | FaceAroundFaceCirculator |
Circulates clockwise around a face and returns an index to the face of the outer half-edge (the target). The best way to declare the circulator is to use the method pcl::geometry::MeshBase::getFaceAroundFaceCirculator (). More... | |
class | FaceAroundVertexCirculator |
Circulates counter-clockwise around a vertex and returns an index to the face of the outgoing half-edge (the target). The best way to declare the circulator is to use the method pcl::geometry::MeshBase::getFaceAroundVertexCirculator (). More... | |
class | FaceIndex |
Index used to access elements in the half-edge mesh. It is basically just a wrapper around an integer with a few added methods. More... | |
class | HalfEdge |
An edge is a connection between two vertices. In a half-edge mesh the edge is split into two half-edges with opposite orientation. Each half-edge stores the index to the terminating vertex, the next half-edge, the previous half-edge and the face it belongs to. The opposite half-edge is accessed implicitly. More... | |
class | HalfEdgeIndex |
Index used to access elements in the half-edge mesh. It is basically just a wrapper around an integer with a few added methods. More... | |
class | IncomingHalfEdgeAroundVertexCirculator |
Circulates counter-clockwise around a vertex and returns an index to the incoming half-edge (the target). The best way to declare the circulator is to use the method pcl::geometry::MeshBase::getIncomingHalfEdgeAroundVertexCirculator (). More... | |
class | InnerHalfEdgeAroundFaceCirculator |
Circulates clockwise around a face and returns an index to the inner half-edge (the target). The best way to declare the circulator is to use the method pcl::geometry::MeshBase::getInnerHalfEdgeAroundFaceCirculator (). More... | |
class | MeshBase |
Base class for the half-edge mesh. More... | |
class | MeshIO |
Read / write the half-edge mesh from / to a file. More... | |
struct | NoData |
No data is associated with the vertices / half-edges / edges / faces. More... | |
class | OuterHalfEdgeAroundFaceCirculator |
Circulates clockwise around a face and returns an index to the outer half-edge (the target). The best way to declare the circulator is to use the method pcl::geometry::MeshBase::getOuterHalfEdgeAroundFaceCirculator (). More... | |
class | OutgoingHalfEdgeAroundVertexCirculator |
Circulates counter-clockwise around a vertex and returns an index to the outgoing half-edge (the target). The best way to declare the circulator is to use the method pcl::geometry::MeshBase::getOutgoingHalfEdgeAroundVertexCirculator (). More... | |
class | PolygonMesh |
General half-edge mesh that can store any polygon with a minimum number of vertices of 3. More... | |
struct | PolygonMeshTag |
Tag describing the type of the mesh. More... | |
class | QuadMesh |
Half-edge mesh that can only store quads. More... | |
struct | QuadMeshTag |
Tag describing the type of the mesh. More... | |
class | TriangleMesh |
Half-edge mesh that can only store triangles. More... | |
struct | TriangleMeshTag |
Tag describing the type of the mesh. More... | |
class | Vertex |
A vertex is a node in the mesh. More... | |
class | VertexAroundFaceCirculator |
Circulates clockwise around a face and returns an index to the terminating vertex of the inner half-edge (the target). The best way to declare the circulator is to use the method pcl::geometry::MeshBase::getVertexAroundFaceCirculator (). More... | |
class | VertexAroundVertexCirculator |
Circulates counter-clockwise around a vertex and returns an index to the terminating vertex of the outgoing half-edge (the target). The best way to declare the circulator is to use the method pcl::geometry::MeshBase::getVertexAroundVertexCirculator (). More... | |
class | VertexIndex |
Index used to access elements in the half-edge mesh. It is basically just a wrapper around an integer with a few added methods. More... | |
Functions | |
template<typename PointT > | |
float | distance (const PointT &p1, const PointT &p2) |
template<class MeshT > | |
void | getBoundBoundaryHalfEdges (const MeshT &mesh, std::vector< typename MeshT::HalfEdgeIndices > &boundary_he_collection, const size_t expected_size=3) |
Get a collection of boundary half-edges for the input mesh. | |
std::ostream & | operator<< (std::ostream &os, const pcl::geometry::VertexIndex &index) |
ostream operator. | |
std::ostream & | operator<< (std::ostream &os, const pcl::geometry::HalfEdgeIndex &index) |
ostream operator. | |
std::ostream & | operator<< (std::ostream &os, const pcl::geometry::EdgeIndex &index) |
ostream operator. | |
std::ostream & | operator<< (std::ostream &os, const pcl::geometry::FaceIndex &index) |
ostream operator. | |
std::istream & | operator>> (std::istream &is, pcl::geometry::VertexIndex &index) |
istream operator. | |
std::istream & | operator>> (std::istream &is, pcl::geometry::HalfEdgeIndex &index) |
istream operator. | |
std::istream & | operator>> (std::istream &is, pcl::geometry::EdgeIndex &index) |
istream operator. | |
std::istream & | operator>> (std::istream &is, pcl::geometry::FaceIndex &index) |
istream operator. | |
template<typename PointT , typename NormalT > | |
void | project (const PointT &point, const PointT &plane_origin, const NormalT &plane_normal, PointT &projected) |
void | project (const Eigen::Vector3f &point, const Eigen::Vector3f &plane_origin, const Eigen::Vector3f &plane_normal, Eigen::Vector3f &projected) |
template<typename PointT > | |
float | squaredDistance (const PointT &p1, const PointT &p2) |
pcl::geometry::EdgeIndex | toEdgeIndex (const HalfEdgeIndex &index) |
Convert the given half-edge index to an edge index. | |
template<class HalfEdgeMeshT > | |
void | toFaceVertexMesh (const HalfEdgeMeshT &half_edge_mesh, pcl::PolygonMesh &face_vertex_mesh) |
Convert a half-edge mesh to a face-vertex mesh. | |
pcl::geometry::HalfEdgeIndex | toHalfEdgeIndex (const EdgeIndex &index, const bool get_first=true) |
Convert the given edge index to a half-edge index. | |
template<class HalfEdgeMeshT > | |
int | toHalfEdgeMesh (const pcl::PolygonMesh &face_vertex_mesh, HalfEdgeMeshT &half_edge_mesh) |
Convert a face-vertex mesh to a half-edge mesh. |
float pcl::geometry::distance | ( | const PointT & | p1, |
const PointT & | p2 | ||
) | [inline] |
Definition at line 60 of file common/include/pcl/common/geometry.h.
void pcl::geometry::getBoundBoundaryHalfEdges | ( | const MeshT & | mesh, |
std::vector< typename MeshT::HalfEdgeIndices > & | boundary_he_collection, | ||
const size_t | expected_size = 3 |
||
) |
Get a collection of boundary half-edges for the input mesh.
[in] | mesh | The input mesh. |
[out] | boundary_he_collection | Collection of boundary half-edges. Each element in the vector is one connected boundary. The whole boundary is the union of all elements. |
[in] | expected_size | If you already know the size of the longest boundary you can tell this here. Defaults to 3 (minimum possible boundary). |
Definition at line 58 of file get_boundary.h.
std::ostream& pcl::geometry::operator<< | ( | std::ostream & | os, |
const pcl::geometry::VertexIndex & | index | ||
) | [inline] |
ostream operator.
Definition at line 174 of file mesh_indices.h.
std::ostream& pcl::geometry::operator<< | ( | std::ostream & | os, |
const pcl::geometry::HalfEdgeIndex & | index | ||
) | [inline] |
ostream operator.
Definition at line 313 of file mesh_indices.h.
std::ostream& pcl::geometry::operator<< | ( | std::ostream & | os, |
const pcl::geometry::EdgeIndex & | index | ||
) | [inline] |
ostream operator.
Definition at line 452 of file mesh_indices.h.
std::ostream& pcl::geometry::operator<< | ( | std::ostream & | os, |
const pcl::geometry::FaceIndex & | index | ||
) | [inline] |
ostream operator.
Definition at line 591 of file mesh_indices.h.
std::istream& pcl::geometry::operator>> | ( | std::istream & | is, |
pcl::geometry::VertexIndex & | index | ||
) | [inline] |
istream operator.
Definition at line 181 of file mesh_indices.h.
std::istream& pcl::geometry::operator>> | ( | std::istream & | is, |
pcl::geometry::HalfEdgeIndex & | index | ||
) | [inline] |
istream operator.
Definition at line 320 of file mesh_indices.h.
std::istream& pcl::geometry::operator>> | ( | std::istream & | is, |
pcl::geometry::EdgeIndex & | index | ||
) | [inline] |
istream operator.
Definition at line 459 of file mesh_indices.h.
std::istream& pcl::geometry::operator>> | ( | std::istream & | is, |
pcl::geometry::FaceIndex & | index | ||
) | [inline] |
istream operator.
Definition at line 598 of file mesh_indices.h.
void pcl::geometry::project | ( | const PointT & | point, |
const PointT & | plane_origin, | ||
const NormalT & | plane_normal, | ||
PointT & | projected | ||
) | [inline] |
[in] | point | Point to be projected |
[in] | plane_origin | The plane origin |
[in] | plane_normal | The plane normal |
[out] | projected | The returned projected point |
Definition at line 81 of file common/include/pcl/common/geometry.h.
void pcl::geometry::project | ( | const Eigen::Vector3f & | point, |
const Eigen::Vector3f & | plane_origin, | ||
const Eigen::Vector3f & | plane_normal, | ||
Eigen::Vector3f & | projected | ||
) | [inline] |
[in] | point | Point to be projected |
[in] | plane_origin | The plane origin |
[in] | plane_normal | The plane normal |
[out] | projected | The returned projected point |
Definition at line 97 of file common/include/pcl/common/geometry.h.
float pcl::geometry::squaredDistance | ( | const PointT & | p1, |
const PointT & | p2 | ||
) | [inline] |
Definition at line 68 of file common/include/pcl/common/geometry.h.
pcl::geometry::EdgeIndex pcl::geometry::toEdgeIndex | ( | const HalfEdgeIndex & | index | ) | [inline] |
Convert the given half-edge index to an edge index.
Definition at line 616 of file mesh_indices.h.
void pcl::geometry::toFaceVertexMesh | ( | const HalfEdgeMeshT & | half_edge_mesh, |
pcl::PolygonMesh & | face_vertex_mesh | ||
) |
Convert a half-edge mesh to a face-vertex mesh.
[in] | half_edge_mesh | The input mesh. |
[out] | face_vertex_mesh | The output mesh. |
Definition at line 58 of file mesh_conversion.h.
pcl::geometry::HalfEdgeIndex pcl::geometry::toHalfEdgeIndex | ( | const EdgeIndex & | index, |
const bool | get_first = true |
||
) | [inline] |
Convert the given edge index to a half-edge index.
[in] | get_first | The first half-edge of the edge is returned if this variable is true; elsewise the second. |
Definition at line 625 of file mesh_indices.h.
int pcl::geometry::toHalfEdgeMesh | ( | const pcl::PolygonMesh & | face_vertex_mesh, |
HalfEdgeMeshT & | half_edge_mesh | ||
) |
Convert a face-vertex mesh to a half-edge mesh.
[in] | face_vertex_mesh | The input mesh. |
[out] | half_edge_mesh | The output mesh. It must have data associated with the vertices. |
Definition at line 89 of file mesh_conversion.h.