The Poisson surface reconstruction algorithm. More...
#include <poisson.h>

Public Types | |
| typedef boost::shared_ptr < const Poisson< PointNT > > | ConstPtr |
| typedef pcl::KdTree< PointNT > | KdTree |
| 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_ |
The Poisson surface reconstruction algorithm.
| typedef boost::shared_ptr<const Poisson<PointNT> > pcl::Poisson< PointNT >::ConstPtr |
Reimplemented from pcl::SurfaceReconstruction< PointNT >.
| typedef pcl::KdTree<PointNT> pcl::Poisson< PointNT >::KdTree |
Reimplemented from pcl::PCLSurfaceBase< PointNT >.
| typedef pcl::KdTree<PointNT>::Ptr pcl::Poisson< PointNT >::KdTreePtr |
Reimplemented from pcl::PCLSurfaceBase< PointNT >.
| typedef pcl::PointCloud<PointNT>::Ptr pcl::Poisson< PointNT >::PointCloudPtr |
Reimplemented from pcl::PCLBase< PointNT >.
| typedef boost::shared_ptr<Poisson<PointNT> > pcl::Poisson< PointNT >::Ptr |
Reimplemented from pcl::SurfaceReconstruction< PointNT >.
| pcl::Poisson< PointNT >::Poisson | ( | ) |
Constructor that sets all the parameters to working default values.
Definition at line 64 of file poisson.hpp.
| pcl::Poisson< PointNT >::~Poisson | ( | ) |
Destructor.
Definition at line 89 of file poisson.hpp.
| 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.
| std::string pcl::Poisson< PointNT >::getClassName | ( | ) | const [inline, protected, virtual] |
Class get name method.
Reimplemented from pcl::PCLSurfaceBase< PointNT >.
| bool pcl::Poisson< PointNT >::getConfidence | ( | ) | [inline] |
| int pcl::Poisson< PointNT >::getDegree | ( | ) | [inline] |
| int pcl::Poisson< PointNT >::getDepth | ( | ) | [inline] |
| int pcl::Poisson< PointNT >::getIsoDivide | ( | ) | [inline] |
| bool pcl::Poisson< PointNT >::getManifold | ( | ) | [inline] |
| int pcl::Poisson< PointNT >::getMinDepth | ( | ) | [inline] |
| bool pcl::Poisson< PointNT >::getOutputPolygons | ( | ) | [inline] |
| float pcl::Poisson< PointNT >::getPointWeight | ( | ) | [inline] |
| float pcl::Poisson< PointNT >::getSamplesPerNode | ( | ) | [inline] |
| float pcl::Poisson< PointNT >::getScale | ( | ) | [inline] |
| int pcl::Poisson< PointNT >::getSolverDivide | ( | ) | [inline] |
| void pcl::Poisson< PointNT >::performReconstruction | ( | pcl::PolygonMesh & | output | ) | [virtual] |
Create the surface.
| [out] | output | the resultant polygonal mesh |
Implements pcl::SurfaceReconstruction< PointNT >.
Definition at line 152 of file poisson.hpp.
| void pcl::Poisson< PointNT >::performReconstruction | ( | pcl::PointCloud< PointNT > & | points, |
| std::vector< pcl::Vertices > & | polygons | ||
| ) | [virtual] |
Create the surface.
| [out] | points | the vertex positions of the resulting mesh |
| [out] | polygons | the connectivity of the resulting mesh |
Implements pcl::SurfaceReconstruction< PointNT >.
Definition at line 232 of file poisson.hpp.
| void pcl::Poisson< PointNT >::setConfidence | ( | bool | confidence | ) | [inline] |
Set the confidence flag.
| [in] | confidence | the given flag |
| void pcl::Poisson< PointNT >::setDegree | ( | int | degree | ) | [inline] |
| void pcl::Poisson< PointNT >::setDepth | ( | int | depth | ) | [inline] |
Set the maximum depth of the tree that will be used for surface reconstruction.
| [in] | depth | the depth parameter |
| 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.
| [in] | iso_divide | the given parameter value |
| void pcl::Poisson< PointNT >::setManifold | ( | bool | manifold | ) | [inline] |
| void pcl::Poisson< PointNT >::setMinDepth | ( | int | min_depth | ) | [inline] |
| void pcl::Poisson< PointNT >::setOutputPolygons | ( | bool | output_polygons | ) | [inline] |
| void pcl::Poisson< PointNT >::setPointWeight | ( | float | point_weight | ) | [inline] |
| 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.
| [in] | samples_per_node | the given parameter value |
| void pcl::Poisson< PointNT >::setScale | ( | float | scale | ) | [inline] |
| 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.
| [in] | solver_divide | the given parameter value |
bool pcl::Poisson< PointNT >::confidence_ [private] |
int pcl::Poisson< PointNT >::degree_ [private] |
int pcl::Poisson< PointNT >::depth_ [private] |
int pcl::Poisson< PointNT >::iso_divide_ [private] |
int pcl::Poisson< PointNT >::kernel_depth_ [private] |
bool pcl::Poisson< PointNT >::manifold_ [private] |
int pcl::Poisson< PointNT >::min_depth_ [private] |
int pcl::Poisson< PointNT >::min_iterations_ [private] |
bool pcl::Poisson< PointNT >::no_clip_tree_ [private] |
bool pcl::Poisson< PointNT >::no_reset_samples_ [private] |
bool pcl::Poisson< PointNT >::non_adaptive_weights_ [private] |
bool pcl::Poisson< PointNT >::output_polygons_ [private] |
float pcl::Poisson< PointNT >::point_weight_ [private] |
int pcl::Poisson< PointNT >::refine_ [private] |
float pcl::Poisson< PointNT >::samples_per_node_ [private] |
float pcl::Poisson< PointNT >::scale_ [private] |
bool pcl::Poisson< PointNT >::show_residual_ [private] |
float pcl::Poisson< PointNT >::solver_accuracy_ [private] |
int pcl::Poisson< PointNT >::solver_divide_ [private] |