Public Types | Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
pcl::Poisson< PointNT > Class Template Reference

The Poisson surface reconstruction algorithm. More...

#include <poisson.h>

Inheritance diagram for pcl::Poisson< PointNT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const Poisson< PointNT > > 
ConstPtr
typedef pcl::KdTree< PointNTKdTree
typedef pcl::KdTree< PointNT >::Ptr KdTreePtr
typedef pcl::PointCloud
< PointNT >::Ptr 
PointCloudPtr
typedef boost::shared_ptr
< Poisson< PointNT > > 
Ptr

Public Member Functions

bool getConfidence ()
 Get the confidence flag.
int getDegree ()
 Get the degree parameter.
int getDepth ()
 Get the depth parameter.
int getIsoDivide ()
 Get the depth at which a block iso-surface extractor should be used to extract the iso-surface.
bool getManifold ()
 Get the manifold flag.
int getMinDepth ()
bool getOutputPolygons ()
 Get whether the algorithm outputs a polygon mesh or a triangle mesh.
float getPointWeight ()
float getSamplesPerNode ()
 Get the minimum number of sample points that should fall within an octree node as the octree construction is adapted to sampling density.
float getScale ()
int getSolverDivide ()
 Get the the depth at which a block Gauss-Seidel solver is used to solve the Laplacian equation.
void performReconstruction (pcl::PolygonMesh &output)
 Create the surface.
void performReconstruction (pcl::PointCloud< PointNT > &points, std::vector< pcl::Vertices > &polygons)
 Create the surface.
 Poisson ()
 Constructor that sets all the parameters to working default values.
void setConfidence (bool confidence)
 Set the confidence flag.
void setDegree (int degree)
 Set the degree parameter.
void setDepth (int depth)
 Set the maximum depth of the tree that will be used for surface reconstruction.
void setIsoDivide (int iso_divide)
 Set the depth at which a block iso-surface extractor should be used to extract the iso-surface.
void setManifold (bool manifold)
 Set the manifold flag.
void setMinDepth (int min_depth)
void setOutputPolygons (bool output_polygons)
 Enabling this flag tells the reconstructor to output a polygon mesh (rather than triangulating the results of Marching Cubes).
void setPointWeight (float point_weight)
void setSamplesPerNode (float samples_per_node)
 Set the minimum number of sample points that should fall within an octree node as the octree construction is adapted to sampling density.
void setScale (float scale)
 Set the ratio between the diameter of the cube used for reconstruction and the diameter of the samples' bounding cube.
void setSolverDivide (int solver_divide)
 Set the the depth at which a block Gauss-Seidel solver is used to solve the Laplacian equation.
 ~Poisson ()
 Destructor.

Protected Member Functions

std::string getClassName () const
 Class get name method.

Private Member Functions

template<int Degree>
void execute (poisson::CoredVectorMeshData &mesh, poisson::Point3D< float > &translate, float &scale)

Private Attributes

bool confidence_
int degree_
int depth_
int iso_divide_
int kernel_depth_
bool manifold_
int min_depth_
int min_iterations_
bool no_clip_tree_
bool no_reset_samples_
bool non_adaptive_weights_
bool output_polygons_
float point_weight_
int refine_
float samples_per_node_
float scale_
bool show_residual_
float solver_accuracy_
int solver_divide_

Detailed Description

template<typename PointNT>
class pcl::Poisson< PointNT >

The Poisson surface reconstruction algorithm.

Note:
Code adapted from Misha Kazhdan: http://www.cs.jhu.edu/~misha/Code/PoissonRecon/
Based on the paper: * Michael Kazhdan, Matthew Bolitho, Hugues Hoppe, "Poisson surface reconstruction", SGP '06 Proceedings of the fourth Eurographics symposium on Geometry processing
Author:
Alexandru-Eugen Ichim

Definition at line 60 of file poisson.h.


Member Typedef Documentation

template<typename PointNT>
typedef boost::shared_ptr<const Poisson<PointNT> > pcl::Poisson< PointNT >::ConstPtr

Reimplemented from pcl::SurfaceReconstruction< PointNT >.

Definition at line 64 of file poisson.h.

template<typename PointNT>
typedef pcl::KdTree<PointNT> pcl::Poisson< PointNT >::KdTree

Reimplemented from pcl::PCLSurfaceBase< PointNT >.

Definition at line 71 of file poisson.h.

template<typename PointNT>
typedef pcl::KdTree<PointNT>::Ptr pcl::Poisson< PointNT >::KdTreePtr

Reimplemented from pcl::PCLSurfaceBase< PointNT >.

Definition at line 72 of file poisson.h.

template<typename PointNT>
typedef pcl::PointCloud<PointNT>::Ptr pcl::Poisson< PointNT >::PointCloudPtr

Reimplemented from pcl::PCLBase< PointNT >.

Definition at line 69 of file poisson.h.

template<typename PointNT>
typedef boost::shared_ptr<Poisson<PointNT> > pcl::Poisson< PointNT >::Ptr

Reimplemented from pcl::SurfaceReconstruction< PointNT >.

Definition at line 63 of file poisson.h.


Constructor & Destructor Documentation

template<typename PointNT >
pcl::Poisson< PointNT >::Poisson ( )

Constructor that sets all the parameters to working default values.

Definition at line 64 of file poisson.hpp.

template<typename PointNT >
pcl::Poisson< PointNT >::~Poisson ( )

Destructor.

Definition at line 89 of file poisson.hpp.


Member Function Documentation

template<typename PointNT >
template<int Degree>
void pcl::Poisson< PointNT >::execute ( poisson::CoredVectorMeshData mesh,
poisson::Point3D< float > &  translate,
float &  scale 
) [private]

TODO OPENMP stuff

Definition at line 95 of file poisson.hpp.

template<typename PointNT>
std::string pcl::Poisson< PointNT >::getClassName ( ) const [inline, protected, virtual]

Class get name method.

Reimplemented from pcl::PCLSurfaceBase< PointNT >.

Definition at line 221 of file poisson.h.

template<typename PointNT>
bool pcl::Poisson< PointNT >::getConfidence ( ) [inline]

Get the confidence flag.

Definition at line 183 of file poisson.h.

template<typename PointNT>
int pcl::Poisson< PointNT >::getDegree ( ) [inline]

Get the degree parameter.

Definition at line 204 of file poisson.h.

template<typename PointNT>
int pcl::Poisson< PointNT >::getDepth ( ) [inline]

Get the depth parameter.

Definition at line 105 of file poisson.h.

template<typename PointNT>
int pcl::Poisson< PointNT >::getIsoDivide ( ) [inline]

Get the depth at which a block iso-surface extractor should be used to extract the iso-surface.

Definition at line 156 of file poisson.h.

template<typename PointNT>
bool pcl::Poisson< PointNT >::getManifold ( ) [inline]

Get the manifold flag.

Definition at line 216 of file poisson.h.

template<typename PointNT>
int pcl::Poisson< PointNT >::getMinDepth ( ) [inline]

Definition at line 111 of file poisson.h.

template<typename PointNT>
bool pcl::Poisson< PointNT >::getOutputPolygons ( ) [inline]

Get whether the algorithm outputs a polygon mesh or a triangle mesh.

Definition at line 194 of file poisson.h.

template<typename PointNT>
float pcl::Poisson< PointNT >::getPointWeight ( ) [inline]

Definition at line 117 of file poisson.h.

template<typename PointNT>
float pcl::Poisson< PointNT >::getSamplesPerNode ( ) [inline]

Get the minimum number of sample points that should fall within an octree node as the octree construction is adapted to sampling density.

Definition at line 171 of file poisson.h.

template<typename PointNT>
float pcl::Poisson< PointNT >::getScale ( ) [inline]

Get the ratio between the diameter of the cube used for reconstruction and the diameter of the samples' bounding cube.

Definition at line 130 of file poisson.h.

template<typename PointNT>
int pcl::Poisson< PointNT >::getSolverDivide ( ) [inline]

Get the the depth at which a block Gauss-Seidel solver is used to solve the Laplacian equation.

Definition at line 143 of file poisson.h.

template<typename PointNT >
void pcl::Poisson< PointNT >::performReconstruction ( pcl::PolygonMesh output) [virtual]

Create the surface.

Parameters:
[out]outputthe resultant polygonal mesh

Implements pcl::SurfaceReconstruction< PointNT >.

Definition at line 152 of file poisson.hpp.

template<typename PointNT >
void pcl::Poisson< PointNT >::performReconstruction ( pcl::PointCloud< PointNT > &  points,
std::vector< pcl::Vertices > &  polygons 
) [virtual]

Create the surface.

Parameters:
[out]pointsthe vertex positions of the resulting mesh
[out]polygonsthe connectivity of the resulting mesh

Implements pcl::SurfaceReconstruction< PointNT >.

Definition at line 232 of file poisson.hpp.

template<typename PointNT>
void pcl::Poisson< PointNT >::setConfidence ( bool  confidence) [inline]

Set the confidence flag.

Note:
Enabling this flag tells the reconstructor to use the size of the normals as confidence information. When the flag is not enabled, all normals are normalized to have unit-length prior to reconstruction.
Parameters:
[in]confidencethe given flag

Definition at line 179 of file poisson.h.

template<typename PointNT>
void pcl::Poisson< PointNT >::setDegree ( int  degree) [inline]

Set the degree parameter.

Parameters:
[in]degreethe given degree

Definition at line 200 of file poisson.h.

template<typename PointNT>
void pcl::Poisson< PointNT >::setDepth ( int  depth) [inline]

Set the maximum depth of the tree that will be used for surface reconstruction.

Note:
Running at depth d corresponds to solving on a voxel grid whose resolution is no larger than 2^d x 2^d x 2^d. Note that since the reconstructor adapts the octree to the sampling density, the specified reconstruction depth is only an upper bound.
Parameters:
[in]depththe depth parameter

Definition at line 101 of file poisson.h.

template<typename PointNT>
void pcl::Poisson< PointNT >::setIsoDivide ( int  iso_divide) [inline]

Set the depth at which a block iso-surface extractor should be used to extract the iso-surface.

Note:
Using this parameter helps reduce the memory overhead at the cost of a small increase in extraction time. (In practice, we have found that for reconstructions of depth 9 or higher a subdivide depth of 7 or 8 can greatly reduce the memory usage.)
Parameters:
[in]iso_dividethe given parameter value

Definition at line 152 of file poisson.h.

template<typename PointNT>
void pcl::Poisson< PointNT >::setManifold ( bool  manifold) [inline]

Set the manifold flag.

Note:
Enabling this flag tells the reconstructor to add the polygon barycenter when triangulating polygons with more than three vertices.
Parameters:
[in]manifoldthe given flag

Definition at line 212 of file poisson.h.

template<typename PointNT>
void pcl::Poisson< PointNT >::setMinDepth ( int  min_depth) [inline]

Definition at line 108 of file poisson.h.

template<typename PointNT>
void pcl::Poisson< PointNT >::setOutputPolygons ( bool  output_polygons) [inline]

Enabling this flag tells the reconstructor to output a polygon mesh (rather than triangulating the results of Marching Cubes).

Parameters:
[in]output_polygonsthe given flag

Definition at line 190 of file poisson.h.

template<typename PointNT>
void pcl::Poisson< PointNT >::setPointWeight ( float  point_weight) [inline]

Definition at line 114 of file poisson.h.

template<typename PointNT>
void pcl::Poisson< PointNT >::setSamplesPerNode ( float  samples_per_node) [inline]

Set the minimum number of sample points that should fall within an octree node as the octree construction is adapted to sampling density.

Note:
For noise-free samples, small values in the range [1.0 - 5.0] can be used. For more noisy samples, larger values in the range [15.0 - 20.0] may be needed to provide a smoother, noise-reduced, reconstruction.
Parameters:
[in]samples_per_nodethe given parameter value

Definition at line 165 of file poisson.h.

template<typename PointNT>
void pcl::Poisson< PointNT >::setScale ( float  scale) [inline]

Set the ratio between the diameter of the cube used for reconstruction and the diameter of the samples' bounding cube.

Parameters:
[in]scalethe given parameter value

Definition at line 124 of file poisson.h.

template<typename PointNT>
void pcl::Poisson< PointNT >::setSolverDivide ( int  solver_divide) [inline]

Set the the depth at which a block Gauss-Seidel solver is used to solve the Laplacian equation.

Note:
Using this parameter helps reduce the memory overhead at the cost of a small increase in reconstruction time. (In practice, we have found that for reconstructions of depth 9 or higher a subdivide depth of 7 or 8 can greatly reduce the memory usage.)
Parameters:
[in]solver_dividethe given parameter value

Definition at line 139 of file poisson.h.


Member Data Documentation

template<typename PointNT>
bool pcl::Poisson< PointNT >::confidence_ [private]

Definition at line 231 of file poisson.h.

template<typename PointNT>
int pcl::Poisson< PointNT >::degree_ [private]

Definition at line 240 of file poisson.h.

template<typename PointNT>
int pcl::Poisson< PointNT >::depth_ [private]

Definition at line 224 of file poisson.h.

template<typename PointNT>
int pcl::Poisson< PointNT >::iso_divide_ [private]

Definition at line 229 of file poisson.h.

template<typename PointNT>
int pcl::Poisson< PointNT >::kernel_depth_ [private]

Definition at line 239 of file poisson.h.

template<typename PointNT>
bool pcl::Poisson< PointNT >::manifold_ [private]

Definition at line 236 of file poisson.h.

template<typename PointNT>
int pcl::Poisson< PointNT >::min_depth_ [private]

Definition at line 225 of file poisson.h.

template<typename PointNT>
int pcl::Poisson< PointNT >::min_iterations_ [private]

Definition at line 243 of file poisson.h.

template<typename PointNT>
bool pcl::Poisson< PointNT >::no_clip_tree_ [private]

Definition at line 235 of file poisson.h.

template<typename PointNT>
bool pcl::Poisson< PointNT >::no_reset_samples_ [private]

Definition at line 234 of file poisson.h.

template<typename PointNT>
bool pcl::Poisson< PointNT >::non_adaptive_weights_ [private]

Definition at line 241 of file poisson.h.

template<typename PointNT>
bool pcl::Poisson< PointNT >::output_polygons_ [private]

Definition at line 232 of file poisson.h.

template<typename PointNT>
float pcl::Poisson< PointNT >::point_weight_ [private]

Definition at line 226 of file poisson.h.

template<typename PointNT>
int pcl::Poisson< PointNT >::refine_ [private]

Definition at line 238 of file poisson.h.

template<typename PointNT>
float pcl::Poisson< PointNT >::samples_per_node_ [private]

Definition at line 230 of file poisson.h.

template<typename PointNT>
float pcl::Poisson< PointNT >::scale_ [private]

Definition at line 227 of file poisson.h.

template<typename PointNT>
bool pcl::Poisson< PointNT >::show_residual_ [private]

Definition at line 242 of file poisson.h.

template<typename PointNT>
float pcl::Poisson< PointNT >::solver_accuracy_ [private]

Definition at line 244 of file poisson.h.

template<typename PointNT>
int pcl::Poisson< PointNT >::solver_divide_ [private]

Definition at line 228 of file poisson.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:43:02