Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
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 (or quad) mesh. More...

#include <organized_fast_mesh.h>

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

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

const Eigen::Vector3f & getViewpoint () const
 Get the viewpoint from where the input point cloud has been acquired. More...
 
 OrganizedFastMesh ()
 Constructor. Triangulation type defaults to QUAD_MESH. More...
 
void setAngleTolerance (float angle_tolerance)
 Set the angle tolerance used for checking whether or not an edge is occluded. Standard values are 5deg to 15deg (input in rad!). Set a value smaller than zero to disable the check for shadowed edges. More...
 
void setDistanceTolerance (float distance_tolerance, bool depth_dependent=false)
 
void setMaxEdgeLength (float a, float b=0.0f, float c=0.0f)
 Set a maximum edge length. Using not only the scalar a, but also b and c, allows for using a distance threshold in the form of: threshold(x) = c*x*x + b*x + a. More...
 
void setTrianglePixelSize (int triangle_size)
 Set the edge length (in pixels) used for constructing the fixed mesh. More...
 
void setTrianglePixelSizeColumns (int triangle_size)
 Set the edge length (in pixels) used for iterating over columns when constructing the fixed mesh. More...
 
void setTrianglePixelSizeRows (int triangle_size)
 Set the edge length (in pixels) used for iterating over rows when constructing the fixed mesh. More...
 
void setTriangulationType (TriangulationType type)
 Set the triangulation type (see TriangulationType) More...
 
void setViewpoint (const Eigen::Vector3f &viewpoint)
 Set the viewpoint from where the input point cloud has been acquired. More...
 
void storeShadowedFaces (bool enable)
 Store shadowed faces or not. More...
 
void unsetMaxEdgeLength ()
 
void useDepthAsDistance (bool enable)
 Use the points' depths (z-coordinates) instead of measured distances (points' distances to the viewpoint). More...
 
virtual ~OrganizedFastMesh ()
 Destructor. More...
 

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. More...
 
void addTriangle (int a, int b, int c, int idx, std::vector< pcl::Vertices > &polygons)
 Add a new triangle to the current polygon mesh. More...
 
bool isShadowed (const PointInT &point_a, const PointInT &point_b)
 Check if a point is shadowed by another point. More...
 
bool isShadowedQuad (const int &a, const int &b, const int &c, const int &d)
 Check if a triangle is shadowed. More...
 
bool isShadowedTriangle (const int &a, const int &b, const int &c)
 Check if a triangle is shadowed. More...
 
bool isValidQuad (const int &a, const int &b, const int &c, const int &d)
 Check if a quad is valid. More...
 
bool isValidTriangle (const int &a, const int &b, const int &c)
 Check if a triangle is valid. More...
 
void makeAdaptiveCutMesh (std::vector< pcl::Vertices > &polygons)
 Create an adaptive cut mesh. More...
 
void makeLeftCutMesh (std::vector< pcl::Vertices > &polygons)
 Create a left cut mesh. More...
 
void makeQuadMesh (std::vector< pcl::Vertices > &polygons)
 Create a quad mesh. More...
 
void makeRightCutMesh (std::vector< pcl::Vertices > &polygons)
 Create a right cut mesh. More...
 
virtual void performReconstruction (std::vector< pcl::Vertices > &polygons)
 Create the surface. More...
 
void performReconstruction (pcl::PolygonMesh &output)
 Create the surface. More...
 
void reconstructPolygons (std::vector< pcl::Vertices > &polygons)
 Perform the actual polygonal reconstruction. More...
 
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. More...
 

Protected Attributes

float cos_angle_tolerance_
 (Cosine of the) angle tolerance used when checking whether or not an edge between two points is shadowed. More...
 
bool distance_dependent_
 flag whether or not distance_tolerance_ is distance dependent (multiplied by the squared distance to the point) or not. More...
 
float distance_tolerance_
 distance tolerance for filtering out shadowed/occluded edges More...
 
float max_edge_length_a_
 max length of edge, scalar component More...
 
float max_edge_length_b_
 max length of edge, scalar component More...
 
float max_edge_length_c_
 max length of edge, scalar component More...
 
bool max_edge_length_dist_dependent_
 flag whether or not max edge length is distance dependent. More...
 
bool max_edge_length_set_
 flag whether or not edges are limited in length More...
 
bool store_shadowed_faces_
 Whether or not shadowed faces are stored, e.g., for exploration. More...
 
int triangle_pixel_size_columns_
 size of triangle edges (in pixels) for iterating over columns More...
 
int triangle_pixel_size_rows_
 size of triangle edges (in pixels) for iterating over rows. More...
 
TriangulationType triangulation_type_
 Type of meshing scheme (quads vs. triangles, left cut vs. right cut ... More...
 
bool use_depth_as_distance_
 flag whether or not the points' depths are used instead of measured distances (points' distances to the viewpoint). This flag may be set using useDepthAsDistance(true) for (RGB-)Depth cameras to skip computations and gain additional speed up. More...
 
Eigen::Vector3f viewpoint_
 Viewpoint from which the point cloud has been acquired (in the same coordinate frame as the data). More...
 

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 (or quad) 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

Definition at line 69 of file organized_fast_mesh.h.

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

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

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 ( )
inlinevirtual

Destructor.

Definition at line 107 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 
)
inlineprotected

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 321 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 
)
inlineprotected

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 303 of file organized_fast_mesh.h.

template<typename PointInT>
const Eigen::Vector3f& pcl::OrganizedFastMesh< PointInT >::getViewpoint ( ) const
inline

Get the viewpoint from where the input point cloud has been acquired.

Definition at line 184 of file organized_fast_mesh.h.

template<typename PointInT>
bool pcl::OrganizedFastMesh< PointInT >::isShadowed ( const PointInT &  point_a,
const PointInT &  point_b 
)
inlineprotected

Check if a point is shadowed by another point.

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

Definition at line 354 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 
)
inlineprotected

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 453 of file organized_fast_mesh.h.

template<typename PointInT>
bool pcl::OrganizedFastMesh< PointInT >::isShadowedTriangle ( const int &  a,
const int &  b,
const int &  c 
)
inlineprotected

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 422 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 
)
inlineprotected

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 437 of file organized_fast_mesh.h.

template<typename PointInT>
bool pcl::OrganizedFastMesh< PointInT >::isValidTriangle ( const int &  a,
const int &  b,
const int &  c 
)
inlineprotected

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 408 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 210 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 169 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 91 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 128 of file organized_fast_mesh.hpp.

template<typename PointInT >
void pcl::OrganizedFastMesh< PointInT >::performReconstruction ( std::vector< pcl::Vertices > &  polygons)
protectedvirtual

Create the surface.

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

Definition at line 70 of file organized_fast_mesh.hpp.

template<typename PointInT >
void pcl::OrganizedFastMesh< PointInT >::performReconstruction ( pcl::PolygonMesh &  output)
protected

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

Definition at line 49 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 77 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 
)
inlineprotected

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 340 of file organized_fast_mesh.h.

template<typename PointInT>
void pcl::OrganizedFastMesh< PointInT >::setAngleTolerance ( float  angle_tolerance)
inline

Set the angle tolerance used for checking whether or not an edge is occluded. Standard values are 5deg to 15deg (input in rad!). Set a value smaller than zero to disable the check for shadowed edges.

Parameters
[in]angle_toleranceAngle tolerance (in rad). Set a value <0 to disable.

Definition at line 204 of file organized_fast_mesh.h.

template<typename PointInT>
void pcl::OrganizedFastMesh< PointInT >::setDistanceTolerance ( float  distance_tolerance,
bool  depth_dependent = false 
)
inline

Definition at line 213 of file organized_fast_mesh.h.

template<typename PointInT>
void pcl::OrganizedFastMesh< PointInT >::setMaxEdgeLength ( float  a,
float  b = 0.0f,
float  c = 0.0f 
)
inline

Set a maximum edge length. Using not only the scalar a, but also b and c, allows for using a distance threshold in the form of: threshold(x) = c*x*x + b*x + a.

Parameters
[in]ascalar coefficient of the (distance-dependent polynom) threshold
[in]blinear coefficient of the (distance-dependent polynom) threshold
[in]cquadratic coefficient of the (distance-dependent polynom) threshold

Definition at line 117 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 139 of file organized_fast_mesh.h.

template<typename PointInT>
void pcl::OrganizedFastMesh< PointInT >::setTrianglePixelSizeColumns ( int  triangle_size)
inline

Set the edge length (in pixels) used for iterating over columns when constructing the fixed mesh.

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

Definition at line 160 of file organized_fast_mesh.h.

template<typename PointInT>
void pcl::OrganizedFastMesh< PointInT >::setTrianglePixelSizeRows ( int  triangle_size)
inline

Set the edge length (in pixels) used for iterating over rows when constructing the fixed mesh.

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

Definition at line 150 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 w.r.t. the depth (z) of the points)

Definition at line 170 of file organized_fast_mesh.h.

template<typename PointInT>
void pcl::OrganizedFastMesh< PointInT >::setViewpoint ( const Eigen::Vector3f &  viewpoint)
inline

Set the viewpoint from where the input point cloud has been acquired.

Parameters
[in]viewpointVector containing the viewpoint coordinates (in the coordinate system of the data)

Definition at line 178 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 193 of file organized_fast_mesh.h.

template<typename PointInT>
void pcl::OrganizedFastMesh< PointInT >::unsetMaxEdgeLength ( )
inline

Definition at line 129 of file organized_fast_mesh.h.

template<typename PointInT>
void pcl::OrganizedFastMesh< PointInT >::useDepthAsDistance ( bool  enable)
inline

Use the points' depths (z-coordinates) instead of measured distances (points' distances to the viewpoint).

Parameters
[in]enableSet to true skips comptations and further speeds up computation by using depth instead of computing distance. false to disable.

Definition at line 226 of file organized_fast_mesh.h.

Member Data Documentation

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

(Cosine of the) angle tolerance used when checking whether or not an edge between two points is shadowed.

Definition at line 260 of file organized_fast_mesh.h.

template<typename PointInT>
bool pcl::OrganizedFastMesh< PointInT >::distance_dependent_
protected

flag whether or not distance_tolerance_ is distance dependent (multiplied by the squared distance to the point) or not.

Definition at line 266 of file organized_fast_mesh.h.

template<typename PointInT>
float pcl::OrganizedFastMesh< PointInT >::distance_tolerance_
protected

distance tolerance for filtering out shadowed/occluded edges

Definition at line 263 of file organized_fast_mesh.h.

template<typename PointInT>
float pcl::OrganizedFastMesh< PointInT >::max_edge_length_a_
protected

max length of edge, scalar component

Definition at line 233 of file organized_fast_mesh.h.

template<typename PointInT>
float pcl::OrganizedFastMesh< PointInT >::max_edge_length_b_
protected

max length of edge, scalar component

Definition at line 235 of file organized_fast_mesh.h.

template<typename PointInT>
float pcl::OrganizedFastMesh< PointInT >::max_edge_length_c_
protected

max length of edge, scalar component

Definition at line 237 of file organized_fast_mesh.h.

template<typename PointInT>
bool pcl::OrganizedFastMesh< PointInT >::max_edge_length_dist_dependent_
protected

flag whether or not max edge length is distance dependent.

Definition at line 242 of file organized_fast_mesh.h.

template<typename PointInT>
bool pcl::OrganizedFastMesh< PointInT >::max_edge_length_set_
protected

flag whether or not edges are limited in length

Definition at line 239 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 257 of file organized_fast_mesh.h.

template<typename PointInT>
int pcl::OrganizedFastMesh< PointInT >::triangle_pixel_size_columns_
protected

size of triangle edges (in pixels) for iterating over columns

Definition at line 248 of file organized_fast_mesh.h.

template<typename PointInT>
int pcl::OrganizedFastMesh< PointInT >::triangle_pixel_size_rows_
protected

size of triangle edges (in pixels) for iterating over rows.

Definition at line 245 of file organized_fast_mesh.h.

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

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

Definition at line 251 of file organized_fast_mesh.h.

template<typename PointInT>
bool pcl::OrganizedFastMesh< PointInT >::use_depth_as_distance_
protected

flag whether or not the points' depths are used instead of measured distances (points' distances to the viewpoint). This flag may be set using useDepthAsDistance(true) for (RGB-)Depth cameras to skip computations and gain additional speed up.

Definition at line 270 of file organized_fast_mesh.h.

template<typename PointInT>
Eigen::Vector3f pcl::OrganizedFastMesh< PointInT >::viewpoint_
protected

Viewpoint from which the point cloud has been acquired (in the same coordinate frame as the data).

Definition at line 254 of file organized_fast_mesh.h.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:43:42