pcl::MovingLeastSquares< PointInT, NormalOutT > Class Template Reference

MovingLeastSquares represent an implementation of the MLS (Moving Least Squares) algorithm for data smoothing and improved normal estimation. More...

#include <mls.h>

Inheritance diagram for pcl::MovingLeastSquares< PointInT, NormalOutT >:
Inheritance graph
[legend]

List of all members.

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.

Detailed Description

template<typename PointInT, typename NormalOutT>
class pcl::MovingLeastSquares< PointInT, NormalOutT >

MovingLeastSquares represent an implementation of the MLS (Moving Least Squares) algorithm for data smoothing and improved normal estimation.

Author:
Zoltan Csaba Marton and Radu Bogdan Rusu

Definition at line 55 of file mls.h.


Member Typedef Documentation

template<typename PointInT, typename NormalOutT>
typedef pcl::KdTree<PointInT> pcl::MovingLeastSquares< PointInT, NormalOutT >::KdTree

Definition at line 63 of file mls.h.

template<typename PointInT, typename NormalOutT>
typedef pcl::KdTree<PointInT>::Ptr pcl::MovingLeastSquares< PointInT, NormalOutT >::KdTreePtr

Definition at line 64 of file mls.h.

template<typename PointInT, typename NormalOutT>
typedef pcl::PointCloud<NormalOutT> pcl::MovingLeastSquares< PointInT, NormalOutT >::NormalCloudOut

Definition at line 66 of file mls.h.

template<typename PointInT, typename NormalOutT>
typedef NormalCloudOut::ConstPtr pcl::MovingLeastSquares< PointInT, NormalOutT >::NormalCloudOutConstPtr

Definition at line 68 of file mls.h.

template<typename PointInT, typename NormalOutT>
typedef NormalCloudOut::Ptr pcl::MovingLeastSquares< PointInT, NormalOutT >::NormalCloudOutPtr

Definition at line 67 of file mls.h.

template<typename PointInT, typename NormalOutT>
typedef pcl::PointCloud<PointInT> pcl::MovingLeastSquares< PointInT, NormalOutT >::PointCloudIn

Definition at line 70 of file mls.h.

template<typename PointInT, typename NormalOutT>
typedef PointCloudIn::ConstPtr pcl::MovingLeastSquares< PointInT, NormalOutT >::PointCloudInConstPtr

Definition at line 72 of file mls.h.

template<typename PointInT, typename NormalOutT>
typedef PointCloudIn::Ptr pcl::MovingLeastSquares< PointInT, NormalOutT >::PointCloudInPtr

Definition at line 71 of file mls.h.

template<typename PointInT, typename NormalOutT>
typedef boost::function<int (int, double, std::vector<int> &, std::vector<float> &)> pcl::MovingLeastSquares< PointInT, NormalOutT >::SearchMethod

Definition at line 74 of file mls.h.


Constructor & Destructor Documentation

template<typename PointInT, typename NormalOutT>
pcl::MovingLeastSquares< PointInT, NormalOutT >::MovingLeastSquares (  )  [inline]

Empty constructor.

Definition at line 77 of file mls.h.


Member Function Documentation

template<typename PointInT, typename NormalOutT>
std::string pcl::MovingLeastSquares< PointInT, NormalOutT >::getClassName (  )  const [inline, private]

Abstract class get name method.

Definition at line 183 of file mls.h.

template<typename PointInT, typename NormalOutT>
NormalCloudOutPtr pcl::MovingLeastSquares< PointInT, NormalOutT >::getOutputNormals (  )  [inline]

Returns a pointer to the point cloud where normal information was saved during reconstruction.

Definition at line 86 of file mls.h.

template<typename PointInT, typename NormalOutT>
bool pcl::MovingLeastSquares< PointInT, NormalOutT >::getPolynomialFit (  )  [inline]

Get the polynomial_fit value (true if the surface and normal are approximated using a polynomial).

Definition at line 117 of file mls.h.

template<typename PointInT, typename NormalOutT>
int pcl::MovingLeastSquares< PointInT, NormalOutT >::getPolynomialOrder (  )  [inline]

Get the order of the polynomial to be fit.

Definition at line 109 of file mls.h.

template<typename PointInT, typename NormalOutT>
KdTreePtr pcl::MovingLeastSquares< PointInT, NormalOutT >::getSearchMethod (  )  [inline]

Get a pointer to the search method used.

Definition at line 101 of file mls.h.

template<typename PointInT, typename NormalOutT>
double pcl::MovingLeastSquares< PointInT, NormalOutT >::getSearchRadius (  )  [inline]

Get the sphere radius used for determining the k-nearest neighbors.

Definition at line 126 of file mls.h.

template<typename PointInT, typename NormalOutT>
double pcl::MovingLeastSquares< PointInT, NormalOutT >::getSqrGaussParam (  )  [inline]

Get the parameter for distance based weighting of neighbors.

Definition at line 135 of file mls.h.

template<typename PointInT , typename NormalOutT >
void pcl::MovingLeastSquares< PointInT, NormalOutT >::performReconstruction ( PointCloudIn output  )  [inline, private]

Abstract surface reconstruction method.

Definition at line 112 of file mls.hpp.

template<typename PointInT , typename NormalOutT >
void pcl::MovingLeastSquares< PointInT, NormalOutT >::reconstruct ( PointCloudIn output  )  [inline]

Base method for surface reconstruction for all points given in <setInputCloud (), setIndices ()>

Parameters:
output the resultant reconstructed surface model

Definition at line 45 of file mls.hpp.

template<typename PointInT, typename NormalOutT>
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.

Parameters:
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

Definition at line 170 of file mls.h.

template<typename PointInT, typename NormalOutT>
void pcl::MovingLeastSquares< PointInT, NormalOutT >::setOutputNormals ( NormalCloudOutPtr  cloud  )  [inline]

Provide a pointer to an point cloud where normal information should be saved.

Note:
This is optional, it can be the same as the parameter to the reconstruction method, but no normals are estimated if it is not set.
Parameters:
cloud the const boost shared pointer to a point cloud with normal

Definition at line 83 of file mls.h.

template<typename PointInT, typename NormalOutT>
void pcl::MovingLeastSquares< PointInT, NormalOutT >::setPolynomialFit ( bool  polynomial_fit  )  [inline]

Sets whether the surface and normal are approximated using a polynomial, or only via tangent estimation.

Parameters:
polynomial_fit set to true for polynomial fit

Definition at line 114 of file mls.h.

template<typename PointInT, typename NormalOutT>
void pcl::MovingLeastSquares< PointInT, NormalOutT >::setPolynomialOrder ( int  order  )  [inline]

Set the order of the polynomial to be fit.

Parameters:
order the order of the polynomial

Definition at line 106 of file mls.h.

template<typename PointInT, typename NormalOutT>
void pcl::MovingLeastSquares< PointInT, NormalOutT >::setSearchMethod ( const KdTreePtr tree  )  [inline]

Provide a pointer to the search object.

Parameters:
tree a pointer to the spatial search object.

Definition at line 92 of file mls.h.

template<typename PointInT, typename NormalOutT>
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.

Parameters:
radius the sphere radius that is to contain all k-nearest neighbors
Note:
Calling this method resets the squared Gaussian parameter to radius * radius !

Definition at line 123 of file mls.h.

template<typename PointInT, typename NormalOutT>
void pcl::MovingLeastSquares< PointInT, NormalOutT >::setSqrGaussParam ( double  sqr_gauss_param  )  [inline]

Set the parameter used for distance based weighting of neighbors (the square of the search radius works best in general).

Note:
sqr_gauss_param the squared Gaussian parameter

Definition at line 132 of file mls.h.


Member Data Documentation

template<typename PointInT, typename NormalOutT>
NormalCloudOutPtr pcl::MovingLeastSquares< PointInT, NormalOutT >::normals_ [protected]

The input point cloud dataset.

Definition at line 144 of file mls.h.

template<typename PointInT, typename NormalOutT>
int pcl::MovingLeastSquares< PointInT, NormalOutT >::nr_coeff_ [private]

Number of coefficients, to be computed from the requested order.

Definition at line 177 of file mls.h.

template<typename PointInT, typename NormalOutT>
int pcl::MovingLeastSquares< PointInT, NormalOutT >::order_ [protected]

The order of the polynomial to be fit.

Definition at line 153 of file mls.h.

template<typename PointInT, typename NormalOutT>
bool pcl::MovingLeastSquares< PointInT, NormalOutT >::polynomial_fit_ [protected]

True if the surface and normal be approximated using a polynomial, false if tangent estimation is sufficient.

Definition at line 156 of file mls.h.

template<typename PointInT, typename NormalOutT>
SearchMethod pcl::MovingLeastSquares< PointInT, NormalOutT >::search_method_ [protected]

The search method template for indices.

Definition at line 147 of file mls.h.

template<typename PointInT, typename NormalOutT>
double pcl::MovingLeastSquares< PointInT, NormalOutT >::search_radius_ [protected]

The nearest neighbors search radius for each point.

Definition at line 159 of file mls.h.

template<typename PointInT, typename NormalOutT>
double pcl::MovingLeastSquares< PointInT, NormalOutT >::sqr_gauss_param_ [protected]

Parameter for distance based weighting of neighbors (search_radius_ * search_radius_ works fine).

Definition at line 162 of file mls.h.

template<typename PointInT, typename NormalOutT>
KdTreePtr pcl::MovingLeastSquares< PointInT, NormalOutT >::tree_ [protected]

A pointer to the spatial search object.

Definition at line 150 of file mls.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


pcl
Author(s): See http://pcl.ros.org/authors for the complete list of authors.
autogenerated on Fri Jan 11 09:57:19 2013