MovingLeastSquares represent an implementation of the MLS (Moving Least Squares) algorithm for data smoothing and improved normal estimation. More...
#include <mls.h>

Public Types | |
| typedef pcl::KdTree< PointInT > | KdTree |
| typedef pcl::KdTree< PointInT > ::Ptr | KdTreePtr |
| typedef pcl::PointCloud < NormalOutT > | NormalCloudOut |
| typedef NormalCloudOut::ConstPtr | NormalCloudOutConstPtr |
| typedef NormalCloudOut::Ptr | NormalCloudOutPtr |
| typedef pcl::PointCloud< PointInT > | PointCloudIn |
| typedef PointCloudIn::ConstPtr | PointCloudInConstPtr |
| typedef PointCloudIn::Ptr | PointCloudInPtr |
| typedef boost::function< int(int, double, std::vector< int > &, std::vector< float > &)> | SearchMethod |
Public Member Functions | |
| NormalCloudOutPtr | getOutputNormals () |
| Returns a pointer to the point cloud where normal information was saved during reconstruction. | |
| bool | getPolynomialFit () |
| Get the polynomial_fit value (true if the surface and normal are approximated using a polynomial). | |
| int | getPolynomialOrder () |
| Get the order of the polynomial to be fit. | |
| KdTreePtr | getSearchMethod () |
| Get a pointer to the search method used. | |
| double | getSearchRadius () |
| Get the sphere radius used for determining the k-nearest neighbors. | |
| double | getSqrGaussParam () |
| Get the parameter for distance based weighting of neighbors. | |
| MovingLeastSquares () | |
| Empty constructor. | |
| void | reconstruct (PointCloudIn &output) |
| Base method for surface reconstruction for all points given in <setInputCloud (), setIndices ()> | |
| void | setOutputNormals (NormalCloudOutPtr cloud) |
| Provide a pointer to an point cloud where normal information should be saved. | |
| void | setPolynomialFit (bool polynomial_fit) |
| Sets whether the surface and normal are approximated using a polynomial, or only via tangent estimation. | |
| void | setPolynomialOrder (int order) |
| Set the order of the polynomial to be fit. | |
| void | setSearchMethod (const KdTreePtr &tree) |
| Provide a pointer to the search object. | |
| void | setSearchRadius (double radius) |
| Set the sphere radius that is to be used for determining the k-nearest neighbors used for fitting. | |
| void | setSqrGaussParam (double sqr_gauss_param) |
| Set the parameter used for distance based weighting of neighbors (the square of the search radius works best in general). | |
Protected Member Functions | |
| int | searchForNeighbors (int index, std::vector< int > &indices, std::vector< float > &sqr_distances) |
| Search for the closest nearest neighbors of a given point using a radius search. | |
Protected Attributes | |
| NormalCloudOutPtr | normals_ |
| The input point cloud dataset. | |
| int | order_ |
| The order of the polynomial to be fit. | |
| bool | polynomial_fit_ |
| SearchMethod | search_method_ |
| The search method template for indices. | |
| double | search_radius_ |
| The nearest neighbors search radius for each point. | |
| double | sqr_gauss_param_ |
| Parameter for distance based weighting of neighbors (search_radius_ * search_radius_ works fine). | |
| KdTreePtr | tree_ |
| A pointer to the spatial search object. | |
Private Member Functions | |
| std::string | getClassName () const |
| Abstract class get name method. | |
| void | performReconstruction (PointCloudIn &output) |
| Abstract surface reconstruction method. | |
Private Attributes | |
| int | nr_coeff_ |
| Number of coefficients, to be computed from the requested order. | |
MovingLeastSquares represent an implementation of the MLS (Moving Least Squares) algorithm for data smoothing and improved normal estimation.
Definition at line 55 of file mls.h.
| typedef pcl::KdTree<PointInT> pcl::MovingLeastSquares< PointInT, NormalOutT >::KdTree |
| typedef pcl::KdTree<PointInT>::Ptr pcl::MovingLeastSquares< PointInT, NormalOutT >::KdTreePtr |
| typedef pcl::PointCloud<NormalOutT> pcl::MovingLeastSquares< PointInT, NormalOutT >::NormalCloudOut |
| typedef NormalCloudOut::ConstPtr pcl::MovingLeastSquares< PointInT, NormalOutT >::NormalCloudOutConstPtr |
| typedef NormalCloudOut::Ptr pcl::MovingLeastSquares< PointInT, NormalOutT >::NormalCloudOutPtr |
| typedef pcl::PointCloud<PointInT> pcl::MovingLeastSquares< PointInT, NormalOutT >::PointCloudIn |
| typedef PointCloudIn::ConstPtr pcl::MovingLeastSquares< PointInT, NormalOutT >::PointCloudInConstPtr |
| typedef PointCloudIn::Ptr pcl::MovingLeastSquares< PointInT, NormalOutT >::PointCloudInPtr |
| typedef boost::function<int (int, double, std::vector<int> &, std::vector<float> &)> pcl::MovingLeastSquares< PointInT, NormalOutT >::SearchMethod |
| pcl::MovingLeastSquares< PointInT, NormalOutT >::MovingLeastSquares | ( | ) | [inline] |
| std::string pcl::MovingLeastSquares< PointInT, NormalOutT >::getClassName | ( | ) | const [inline, private] |
| NormalCloudOutPtr pcl::MovingLeastSquares< PointInT, NormalOutT >::getOutputNormals | ( | ) | [inline] |
| bool pcl::MovingLeastSquares< PointInT, NormalOutT >::getPolynomialFit | ( | ) | [inline] |
| int pcl::MovingLeastSquares< PointInT, NormalOutT >::getPolynomialOrder | ( | ) | [inline] |
| KdTreePtr pcl::MovingLeastSquares< PointInT, NormalOutT >::getSearchMethod | ( | ) | [inline] |
| double pcl::MovingLeastSquares< PointInT, NormalOutT >::getSearchRadius | ( | ) | [inline] |
| double pcl::MovingLeastSquares< PointInT, NormalOutT >::getSqrGaussParam | ( | ) | [inline] |
| void pcl::MovingLeastSquares< PointInT, NormalOutT >::performReconstruction | ( | PointCloudIn & | output | ) | [inline, private] |
| void pcl::MovingLeastSquares< PointInT, NormalOutT >::reconstruct | ( | PointCloudIn & | output | ) | [inline] |
| int pcl::MovingLeastSquares< PointInT, NormalOutT >::searchForNeighbors | ( | int | index, | |
| std::vector< int > & | indices, | |||
| std::vector< float > & | sqr_distances | |||
| ) | [inline, protected] |
Search for the closest nearest neighbors of a given point using a radius search.
| index | the index of the query point | |
| indices | the resultant vector of indices representing the k-nearest neighbors | |
| sqr_distances | the resultant squared distances from the query point to the k-nearest neighbors |
| void pcl::MovingLeastSquares< PointInT, NormalOutT >::setOutputNormals | ( | NormalCloudOutPtr | cloud | ) | [inline] |
Provide a pointer to an point cloud where normal information should be saved.
| cloud | the const boost shared pointer to a point cloud with normal |
| void pcl::MovingLeastSquares< PointInT, NormalOutT >::setPolynomialFit | ( | bool | polynomial_fit | ) | [inline] |
| void pcl::MovingLeastSquares< PointInT, NormalOutT >::setPolynomialOrder | ( | int | order | ) | [inline] |
| void pcl::MovingLeastSquares< PointInT, NormalOutT >::setSearchMethod | ( | const KdTreePtr & | tree | ) | [inline] |
| void pcl::MovingLeastSquares< PointInT, NormalOutT >::setSearchRadius | ( | double | radius | ) | [inline] |
Set the sphere radius that is to be used for determining the k-nearest neighbors used for fitting.
| radius | the sphere radius that is to contain all k-nearest neighbors |
| void pcl::MovingLeastSquares< PointInT, NormalOutT >::setSqrGaussParam | ( | double | sqr_gauss_param | ) | [inline] |
NormalCloudOutPtr pcl::MovingLeastSquares< PointInT, NormalOutT >::normals_ [protected] |
int pcl::MovingLeastSquares< PointInT, NormalOutT >::nr_coeff_ [private] |
int pcl::MovingLeastSquares< PointInT, NormalOutT >::order_ [protected] |
bool pcl::MovingLeastSquares< PointInT, NormalOutT >::polynomial_fit_ [protected] |
SearchMethod pcl::MovingLeastSquares< PointInT, NormalOutT >::search_method_ [protected] |
double pcl::MovingLeastSquares< PointInT, NormalOutT >::search_radius_ [protected] |
double pcl::MovingLeastSquares< PointInT, NormalOutT >::sqr_gauss_param_ [protected] |
KdTreePtr pcl::MovingLeastSquares< PointInT, NormalOutT >::tree_ [protected] |