Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
pcl::OrganizedFastMesh< PointInT > Class Template Reference

Simple triangulation/surface reconstruction for organized point clouds. Neighboring points (pixels in image space) are connected to construct a triangular mesh. More...

#include <organized_fast_mesh.h>

Inheritance diagram for pcl::OrganizedFastMesh< PointInT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const OrganizedFastMesh
< PointInT > > 
ConstPtr
typedef pcl::PointCloud
< PointInT >::Ptr 
PointCloudPtr
typedef std::vector
< pcl::Vertices
Polygons
typedef boost::shared_ptr
< OrganizedFastMesh< PointInT > > 
Ptr
enum  TriangulationType { TRIANGLE_RIGHT_CUT, TRIANGLE_LEFT_CUT, TRIANGLE_ADAPTIVE_CUT, QUAD_MESH }

Public Member Functions

 OrganizedFastMesh ()
 Constructor. Triangulation type defaults to QUAD_MESH.
void setMaxEdgeLength (float max_edge_length)
 Set a maximum edge length. TODO: Implement!
void setTrianglePixelSize (int triangle_size)
 Set the edge length (in pixels) used for constructing the fixed mesh.
void setTriangulationType (TriangulationType type)
 Set the triangulation type (see TriangulationType)
void storeShadowedFaces (bool enable)
 Store shadowed faces or not.
virtual ~OrganizedFastMesh ()
 Destructor.

Protected Member Functions

void addQuad (int a, int b, int c, int d, int idx, std::vector< pcl::Vertices > &polygons)
 Add a new quad to the current polygon mesh.
void addTriangle (int a, int b, int c, int idx, std::vector< pcl::Vertices > &polygons)
 Add a new triangle to the current polygon mesh.
bool isShadowed (const PointInT &point_a, const PointInT &point_b)
 Check if a point is shadowed by another point.
bool isShadowedQuad (const int &a, const int &b, const int &c, const int &d)
 Check if a triangle is shadowed.
bool isShadowedTriangle (const int &a, const int &b, const int &c)
 Check if a triangle is shadowed.
bool isValidQuad (const int &a, const int &b, const int &c, const int &d)
 Check if a quad is valid.
bool isValidTriangle (const int &a, const int &b, const int &c)
 Check if a triangle is valid.
void makeAdaptiveCutMesh (std::vector< pcl::Vertices > &polygons)
 Create an adaptive cut mesh.
void makeLeftCutMesh (std::vector< pcl::Vertices > &polygons)
 Create a left cut mesh.
void makeQuadMesh (std::vector< pcl::Vertices > &polygons)
 Create a quad mesh.
void makeRightCutMesh (std::vector< pcl::Vertices > &polygons)
 Create a right cut mesh.
virtual void performReconstruction (std::vector< pcl::Vertices > &polygons)
 Create the surface.
void performReconstruction (pcl::PolygonMesh &output)
 Create the surface.
void reconstructPolygons (std::vector< pcl::Vertices > &polygons)
 Perform the actual polygonal reconstruction.
void resetPointData (const int &point_index, pcl::PolygonMesh &mesh, const float &value=0.0f, int field_x_idx=0, int field_y_idx=1, int field_z_idx=2)
 Set (all) coordinates of a particular point to the specified value.

Protected Attributes

float cos_angle_tolerance_
float max_edge_length_squared_
 max (squared) length of edge
bool store_shadowed_faces_
 Whether or not shadowed faces are stored, e.g., for exploration.
int triangle_pixel_size_
 size of triangle endges (in pixels)
TriangulationType triangulation_type_
 Type of meshin scheme (quads vs. triangles, left cut vs. right cut ...

Detailed Description

template<typename PointInT>
class pcl::OrganizedFastMesh< PointInT >

Simple triangulation/surface reconstruction for organized point clouds. Neighboring points (pixels in image space) are connected to construct a triangular mesh.

Note:
If you use this code in any academic work, please cite: D. Holz and S. Behnke. Fast Range Image Segmentation and Smoothing using Approximate Surface Reconstruction and Region Growing. In Proceedings of the 12th International Conference on Intelligent Autonomous Systems (IAS), Jeju Island, Korea, June 26-29 2012. http://purl.org/holz/papers/holz_2012_ias.pdf
Author:
Dirk Holz, Radu B. Rusu

Definition at line 65 of file organized_fast_mesh.h.


Member Typedef Documentation

template<typename PointInT>
typedef boost::shared_ptr<const OrganizedFastMesh<PointInT> > pcl::OrganizedFastMesh< PointInT >::ConstPtr

Reimplemented from pcl::MeshConstruction< PointInT >.

Definition at line 69 of file organized_fast_mesh.h.

template<typename PointInT>
typedef pcl::PointCloud<PointInT>::Ptr pcl::OrganizedFastMesh< PointInT >::PointCloudPtr

Reimplemented from pcl::PCLBase< PointInT >.

Definition at line 74 of file organized_fast_mesh.h.

template<typename PointInT>
typedef std::vector<pcl::Vertices> pcl::OrganizedFastMesh< PointInT >::Polygons

Definition at line 76 of file organized_fast_mesh.h.

template<typename PointInT>
typedef boost::shared_ptr<OrganizedFastMesh<PointInT> > pcl::OrganizedFastMesh< PointInT >::Ptr

Reimplemented from pcl::MeshConstruction< PointInT >.

Definition at line 68 of file organized_fast_mesh.h.


Member Enumeration Documentation

template<typename PointInT>
enum pcl::OrganizedFastMesh::TriangulationType
Enumerator:
TRIANGLE_RIGHT_CUT 
TRIANGLE_LEFT_CUT 
TRIANGLE_ADAPTIVE_CUT 
QUAD_MESH 

Definition at line 78 of file organized_fast_mesh.h.


Constructor & Destructor Documentation

template<typename PointInT>
pcl::OrganizedFastMesh< PointInT >::OrganizedFastMesh ( ) [inline]

Constructor. Triangulation type defaults to QUAD_MESH.

Definition at line 87 of file organized_fast_mesh.h.

template<typename PointInT>
virtual pcl::OrganizedFastMesh< PointInT >::~OrganizedFastMesh ( ) [inline, virtual]

Destructor.

Definition at line 98 of file organized_fast_mesh.h.


Member Function Documentation

template<typename PointInT>
void pcl::OrganizedFastMesh< PointInT >::addQuad ( int  a,
int  b,
int  c,
int  d,
int  idx,
std::vector< pcl::Vertices > &  polygons 
) [inline, protected]

Add a new quad to the current polygon mesh.

Parameters:
[in]aindex of the first vertex
[in]bindex of the second vertex
[in]cindex of the third vertex
[in]dindex of the fourth vertex
[in]idxthe index in the set of polygon vertices (assumes idx is valid in polygons)
[out]polygonsthe polygon mesh to be updated

Definition at line 201 of file organized_fast_mesh.h.

template<typename PointInT>
void pcl::OrganizedFastMesh< PointInT >::addTriangle ( int  a,
int  b,
int  c,
int  idx,
std::vector< pcl::Vertices > &  polygons 
) [inline, protected]

Add a new triangle to the current polygon mesh.

Parameters:
[in]aindex of the first vertex
[in]bindex of the second vertex
[in]cindex of the third vertex
[in]idxthe index in the set of polygon vertices (assumes idx is valid in polygons)
[out]polygonsthe polygon mesh to be updated

Definition at line 183 of file organized_fast_mesh.h.

template<typename PointInT>
bool pcl::OrganizedFastMesh< PointInT >::isShadowed ( const PointInT &  point_a,
const PointInT &  point_b 
) [inline, protected]

Check if a point is shadowed by another point.

Parameters:
[in]point_athe first point
[in]point_bthe second point

Definition at line 234 of file organized_fast_mesh.h.

template<typename PointInT>
bool pcl::OrganizedFastMesh< PointInT >::isShadowedQuad ( const int &  a,
const int &  b,
const int &  c,
const int &  d 
) [inline, protected]

Check if a triangle is shadowed.

Parameters:
[in]aindex of the first vertex
[in]bindex of the second vertex
[in]cindex of the third vertex
[in]dindex of the fourth vertex

Definition at line 299 of file organized_fast_mesh.h.

template<typename PointInT>
bool pcl::OrganizedFastMesh< PointInT >::isShadowedTriangle ( const int &  a,
const int &  b,
const int &  c 
) [inline, protected]

Check if a triangle is shadowed.

Parameters:
[in]aindex of the first vertex
[in]bindex of the second vertex
[in]cindex of the third vertex

Definition at line 268 of file organized_fast_mesh.h.

template<typename PointInT>
bool pcl::OrganizedFastMesh< PointInT >::isValidQuad ( const int &  a,
const int &  b,
const int &  c,
const int &  d 
) [inline, protected]

Check if a quad is valid.

Parameters:
[in]aindex of the first vertex
[in]bindex of the second vertex
[in]cindex of the third vertex
[in]dindex of the fourth vertex

Definition at line 283 of file organized_fast_mesh.h.

template<typename PointInT>
bool pcl::OrganizedFastMesh< PointInT >::isValidTriangle ( const int &  a,
const int &  b,
const int &  c 
) [inline, protected]

Check if a triangle is valid.

Parameters:
[in]aindex of the first vertex
[in]bindex of the second vertex
[in]cindex of the third vertex

Definition at line 254 of file organized_fast_mesh.h.

template<typename PointInT >
void pcl::OrganizedFastMesh< PointInT >::makeAdaptiveCutMesh ( std::vector< pcl::Vertices > &  polygons) [protected]

Create an adaptive cut mesh.

Parameters:
[out]polygonsthe resultant mesh

Definition at line 209 of file organized_fast_mesh.hpp.

template<typename PointInT >
void pcl::OrganizedFastMesh< PointInT >::makeLeftCutMesh ( std::vector< pcl::Vertices > &  polygons) [protected]

Create a left cut mesh.

Parameters:
[out]polygonsthe resultant mesh

Definition at line 168 of file organized_fast_mesh.hpp.

template<typename PointInT >
void pcl::OrganizedFastMesh< PointInT >::makeQuadMesh ( std::vector< pcl::Vertices > &  polygons) [protected]

Create a quad mesh.

Parameters:
[out]polygonsthe resultant mesh

Definition at line 90 of file organized_fast_mesh.hpp.

template<typename PointInT >
void pcl::OrganizedFastMesh< PointInT >::makeRightCutMesh ( std::vector< pcl::Vertices > &  polygons) [protected]

Create a right cut mesh.

Parameters:
[out]polygonsthe resultant mesh

Definition at line 127 of file organized_fast_mesh.hpp.

template<typename PointInT >
void pcl::OrganizedFastMesh< PointInT >::performReconstruction ( std::vector< pcl::Vertices > &  polygons) [protected, virtual]

Create the surface.

Parameters:
[out]polygonsthe resultant polygons, as a set of vertices. The Vertices structure contains an array of point indices.

Implements pcl::MeshConstruction< PointInT >.

Definition at line 69 of file organized_fast_mesh.hpp.

template<typename PointInT >
void pcl::OrganizedFastMesh< PointInT >::performReconstruction ( pcl::PolygonMesh output) [protected, virtual]

Create the surface.

Simply uses image indices to create an initial polygonal mesh for organized point clouds. indices_ are ignored!

Parameters:
[out]outputthe resultant polygonal mesh

Implements pcl::MeshConstruction< PointInT >.

Definition at line 48 of file organized_fast_mesh.hpp.

template<typename PointInT >
void pcl::OrganizedFastMesh< PointInT >::reconstructPolygons ( std::vector< pcl::Vertices > &  polygons) [protected]

Perform the actual polygonal reconstruction.

Parameters:
[out]polygonsthe resultant polygons

Definition at line 76 of file organized_fast_mesh.hpp.

template<typename PointInT>
void pcl::OrganizedFastMesh< PointInT >::resetPointData ( const int &  point_index,
pcl::PolygonMesh mesh,
const float &  value = 0.0f,
int  field_x_idx = 0,
int  field_y_idx = 1,
int  field_z_idx = 2 
) [inline, protected]

Set (all) coordinates of a particular point to the specified value.

Parameters:
[in]point_indexindex of point
[out]meshto modify
[in]valuevalue to use when re-setting
[in]field_x_idxthe X coordinate of the point
[in]field_y_idxthe Y coordinate of the point
[in]field_z_idxthe Z coordinate of the point

Definition at line 220 of file organized_fast_mesh.h.

template<typename PointInT>
void pcl::OrganizedFastMesh< PointInT >::setMaxEdgeLength ( float  max_edge_length) [inline]

Set a maximum edge length. TODO: Implement!

Parameters:
[in]max_edge_lengththe maximum edge length

Definition at line 104 of file organized_fast_mesh.h.

template<typename PointInT>
void pcl::OrganizedFastMesh< PointInT >::setTrianglePixelSize ( int  triangle_size) [inline]

Set the edge length (in pixels) used for constructing the fixed mesh.

Parameters:
[in]triangle_sizeedge length in pixels (Default: 1 = neighboring pixels are connected)

Definition at line 114 of file organized_fast_mesh.h.

template<typename PointInT>
void pcl::OrganizedFastMesh< PointInT >::setTriangulationType ( TriangulationType  type) [inline]

Set the triangulation type (see TriangulationType)

Parameters:
[in]typequad mesh, triangle mesh with fixed left, right cut, or adaptive cut (splits a quad wrt. the depth (z) of the points)

Definition at line 124 of file organized_fast_mesh.h.

template<typename PointInT>
void pcl::OrganizedFastMesh< PointInT >::storeShadowedFaces ( bool  enable) [inline]

Store shadowed faces or not.

Parameters:
[in]enableset to true to store shadowed faces

Definition at line 133 of file organized_fast_mesh.h.


Member Data Documentation

template<typename PointInT>
float pcl::OrganizedFastMesh< PointInT >::cos_angle_tolerance_ [protected]

Definition at line 151 of file organized_fast_mesh.h.

template<typename PointInT>
float pcl::OrganizedFastMesh< PointInT >::max_edge_length_squared_ [protected]

max (squared) length of edge

Definition at line 140 of file organized_fast_mesh.h.

template<typename PointInT>
bool pcl::OrganizedFastMesh< PointInT >::store_shadowed_faces_ [protected]

Whether or not shadowed faces are stored, e.g., for exploration.

Definition at line 149 of file organized_fast_mesh.h.

template<typename PointInT>
int pcl::OrganizedFastMesh< PointInT >::triangle_pixel_size_ [protected]

size of triangle endges (in pixels)

Definition at line 143 of file organized_fast_mesh.h.

template<typename PointInT>
TriangulationType pcl::OrganizedFastMesh< PointInT >::triangulation_type_ [protected]

Type of meshin scheme (quads vs. triangles, left cut vs. right cut ...

Definition at line 146 of file organized_fast_mesh.h.


The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:42:31