SurfaceReconstruction represents the base surface reconstruction class. More...
#include <reconstruction.h>
Public Types | |
typedef pcl::KdTree< PointInT > | KdTree |
typedef pcl::KdTree< PointInT > ::Ptr | KdTreePtr |
typedef boost::function< int(int, double, std::vector< int > &, std::vector< float > &)> | SearchMethod |
Public Member Functions | |
KdTreePtr | getSearchMethod () |
Get a pointer to the search method used. | |
void | reconstruct (pcl::PolygonMesh &output) |
Base method for surface reconstruction for all points given in <setInputCloud (), setIndices ()> | |
void | setSearchMethod (const KdTreePtr &tree) |
Provide a pointer to the search object. | |
SurfaceReconstruction () | |
Constructor. | |
Protected Member Functions | |
virtual std::string | getClassName () const |
Abstract class get name method. | |
virtual void | performReconstruction (pcl::PolygonMesh &output)=0 |
Abstract surface reconstruction method. | |
Protected Attributes | |
SearchMethod | search_method_ |
The search method template for indices. | |
KdTreePtr | tree_ |
A pointer to the spatial search object. |
SurfaceReconstruction represents the base surface reconstruction class.
Definition at line 54 of file reconstruction.h.
typedef pcl::KdTree<PointInT> pcl::SurfaceReconstruction< PointInT >::KdTree |
Reimplemented in pcl::GreedyProjectionTriangulation< PointInT >, and pcl::GridProjection< PointNT >.
Definition at line 62 of file reconstruction.h.
typedef pcl::KdTree<PointInT>::Ptr pcl::SurfaceReconstruction< PointInT >::KdTreePtr |
Reimplemented in pcl::GreedyProjectionTriangulation< PointInT >, and pcl::GridProjection< PointNT >.
Definition at line 63 of file reconstruction.h.
typedef boost::function<int (int, double, std::vector<int> &, std::vector<float> &)> pcl::SurfaceReconstruction< PointInT >::SearchMethod |
Definition at line 65 of file reconstruction.h.
pcl::SurfaceReconstruction< PointInT >::SurfaceReconstruction | ( | ) | [inline] |
Constructor.
Definition at line 68 of file reconstruction.h.
virtual std::string pcl::SurfaceReconstruction< PointInT >::getClassName | ( | ) | const [inline, protected, virtual] |
Abstract class get name method.
Reimplemented in pcl::GreedyProjectionTriangulation< PointInT >, and pcl::GridProjection< PointNT >.
Definition at line 102 of file reconstruction.h.
KdTreePtr pcl::SurfaceReconstruction< PointInT >::getSearchMethod | ( | ) | [inline] |
Get a pointer to the search method used.
Definition at line 89 of file reconstruction.h.
virtual void pcl::SurfaceReconstruction< PointInT >::performReconstruction | ( | pcl::PolygonMesh & | output | ) | [protected, pure virtual] |
Abstract surface reconstruction method.
Implemented in pcl::GreedyProjectionTriangulation< PointInT >, and pcl::GridProjection< PointNT >.
void pcl::SurfaceReconstruction< PointInT >::reconstruct | ( | pcl::PolygonMesh & | output | ) | [inline] |
Base method for surface reconstruction for all points given in <setInputCloud (), setIndices ()>
output | the resultant reconstructed surface model |
NOTE: passing in boost shared pointer with * as const& should be OK here
NOTE: usually the number of triangles is around twice the number of vertices
Definition at line 43 of file reconstruction.hpp.
void pcl::SurfaceReconstruction< PointInT >::setSearchMethod | ( | const KdTreePtr & | tree | ) | [inline] |
Provide a pointer to the search object.
tree | a pointer to the spatial search object. |
Definition at line 80 of file reconstruction.h.
SearchMethod pcl::SurfaceReconstruction< PointInT >::search_method_ [protected] |
The search method template for indices.
Definition at line 93 of file reconstruction.h.
KdTreePtr pcl::SurfaceReconstruction< PointInT >::tree_ [protected] |
A pointer to the spatial search object.
Definition at line 96 of file reconstruction.h.