Point Cloud Library (PCL)  1.8.1-dev
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
List of all members | Public Member Functions | Protected Member Functions
pcl::NormalRefinement< NormalT > Class Template Reference

Normal vector refinement class More...

#include <pcl/filters/normal_refinement.h>

+ Inheritance diagram for pcl::NormalRefinement< NormalT >:

Public Member Functions

 NormalRefinement ()
 Empty constructor, sets default convergence parameters. More...
 
 NormalRefinement (const std::vector< std::vector< int > > &k_indices, const std::vector< std::vector< float > > &k_sqr_distances)
 Constructor for setting correspondences, sets default convergence parameters. More...
 
void setCorrespondences (const std::vector< std::vector< int > > &k_indices, const std::vector< std::vector< float > > &k_sqr_distances)
 Set correspondences calculated from nearest neighbor search. More...
 
void getCorrespondences (std::vector< std::vector< int > > &k_indices, std::vector< std::vector< float > > &k_sqr_distances)
 Get correspondences (copy) More...
 
void setMaxIterations (unsigned int max_iterations)
 Set maximum iterations. More...
 
unsigned int getMaxIterations ()
 Get maximum iterations. More...
 
void setConvergenceThreshold (float convergence_threshold)
 Set convergence threshold. More...
 
float getConvergenceThreshold ()
 Get convergence threshold. More...
 
- Public Member Functions inherited from pcl::Filter< NormalT >
 Filter (bool extract_removed_indices=false)
 Empty constructor. More...
 
virtual ~Filter ()
 Empty destructor. More...
 
IndicesConstPtr const getRemovedIndices () const
 Get the point indices being removed. More...
 
void getRemovedIndices (PointIndices &pi)
 Get the point indices being removed. More...
 
void filter (PointCloud &output)
 Calls the filtering method and returns the filtered dataset in output. More...
 
- Public Member Functions inherited from pcl::PCLBase< NormalT >
 PCLBase ()
 Empty constructor. More...
 
 PCLBase (const PCLBase &base)
 Copy constructor. More...
 
virtual ~PCLBase ()
 Destructor. More...
 
virtual void setInputCloud (const PointCloudConstPtr &cloud)
 Provide a pointer to the input dataset. More...
 
PointCloudConstPtr const getInputCloud () const
 Get a pointer to the input point cloud dataset. More...
 
virtual void setIndices (const IndicesPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (const IndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (const PointIndicesConstPtr &indices)
 Provide a pointer to the vector of indices that represents the input data. More...
 
virtual void setIndices (size_t row_start, size_t col_start, size_t nb_rows, size_t nb_cols)
 Set the indices for the points laying within an interest region of the point cloud. More...
 
IndicesPtr const getIndices ()
 Get a pointer to the vector of indices used. More...
 
IndicesConstPtr const getIndices () const
 Get a pointer to the vector of indices used. More...
 
const NormalToperator[] (size_t pos) const
 Override PointCloud operator[] to shorten code. More...
 

Protected Member Functions

void applyFilter (PointCloud &output)
 Filter a Point Cloud. More...
 
- Protected Member Functions inherited from pcl::Filter< NormalT >
virtual void applyFilter (PointCloud &output)=0
 Abstract filter method. More...
 
const std::string & getClassName () const
 Get a string representation of the name of this class. More...
 
- Protected Member Functions inherited from pcl::PCLBase< NormalT >
bool initCompute ()
 This method should get called before starting the actual computation. More...
 
bool deinitCompute ()
 This method should get called after finishing the actual computation. More...
 

Additional Inherited Members

- Public Types inherited from pcl::Filter< NormalT >
typedef boost::shared_ptr
< Filter< NormalT > > 
Ptr
 
typedef boost::shared_ptr
< const Filter< NormalT > > 
ConstPtr
 
typedef pcl::PointCloud< NormalTPointCloud
 
typedef PointCloud::Ptr PointCloudPtr
 
typedef PointCloud::ConstPtr PointCloudConstPtr
 
- Public Types inherited from pcl::PCLBase< NormalT >
typedef pcl::PointCloud< NormalTPointCloud
 
typedef PointCloud::Ptr PointCloudPtr
 
typedef PointCloud::ConstPtr PointCloudConstPtr
 
typedef boost::shared_ptr
< PointIndices
PointIndicesPtr
 
typedef boost::shared_ptr
< PointIndices const > 
PointIndicesConstPtr
 
- Protected Attributes inherited from pcl::Filter< NormalT >
IndicesPtr removed_indices_
 Indices of the points that are removed. More...
 
std::string filter_name_
 The filter name. More...
 
bool extract_removed_indices_
 Set to true if we want to return the indices of the removed points. More...
 
- Protected Attributes inherited from pcl::PCLBase< NormalT >
PointCloudConstPtr input_
 The input point cloud dataset. More...
 
IndicesPtr indices_
 A pointer to the vector of point indices to use. More...
 
bool use_indices_
 Set to true if point indices are used. More...
 
bool fake_indices_
 If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud. More...
 

Detailed Description

template<typename NormalT>
class pcl::NormalRefinement< NormalT >

Normal vector refinement class

This class refines a set of already estimated normals by iteratively updating each normal to the (weighted) mean of all normals in its neighborhood. The intention is that you reuse the same point correspondences as used when estimating the original normals in order to avoid repeating a nearest neighbor search.

Note
This class avoids points for which a NaN is encountered in the neighborhood. In the special case where a point has only NaNs in its neighborhood, the resultant refined normal will be set to zero, i.e. this class only produces finite normals.

Usage example:

// Input point cloud
// Fill cloud...
// Estimated and refined normals
pcl::PointCloud<NormalT> normals_refined;
// Search parameters
const int k = 5;
std::vector<std::vector<int> > k_indices;
std::vector<std::vector<float> > k_sqr_distances;
// Run search
search.setInputCloud (cloud.makeShared ());
search.nearestKSearch (cloud, std::vector<int> (), k, k_indices, k_sqr_distances);
// Use search results for normal estimation
for (unsigned int i = 0; i < cloud.size (); ++i)
{
NormalT normal;
ne.computePointNormal (cloud, k_indices[i]
normal.normal_x, normal.normal_y, normal.normal_z, normal.curvature);
normal.normal_x, normal.normal_y, normal.normal_z);
normals.push_back (normal);
}
// Run refinement using search results
pcl::NormalRefinement<NormalT> nr (k_indices, k_sqr_distances);
nr.setInputCloud (normals.makeShared ());
nr.filter (normals_refined);
Author
Anders Glent Buch

Definition at line 188 of file normal_refinement.h.

Constructor & Destructor Documentation

template<typename NormalT>
pcl::NormalRefinement< NormalT >::NormalRefinement ( )
inline
template<typename NormalT>
pcl::NormalRefinement< NormalT >::NormalRefinement ( const std::vector< std::vector< int > > &  k_indices,
const std::vector< std::vector< float > > &  k_sqr_distances 
)
inline

Constructor for setting correspondences, sets default convergence parameters.

Parameters
k_indicesindices of neighboring points
k_sqr_distancessquared distances to the neighboring points

Definition at line 213 of file normal_refinement.h.

References pcl::Filter< NormalT >::filter_name_, pcl::NormalRefinement< NormalT >::setConvergenceThreshold(), pcl::NormalRefinement< NormalT >::setCorrespondences(), and pcl::NormalRefinement< NormalT >::setMaxIterations().

Member Function Documentation

template<typename NormalT >
void pcl::NormalRefinement< NormalT >::applyFilter ( PointCloud &  output)
protected

Filter a Point Cloud.

Parameters
outputthe resultant point cloud message

Definition at line 48 of file normal_refinement.hpp.

References pcl::refineNormal().

template<typename NormalT>
float pcl::NormalRefinement< NormalT >::getConvergenceThreshold ( )
inline

Get convergence threshold.

Returns
convergence threshold

Definition at line 275 of file normal_refinement.h.

template<typename NormalT>
void pcl::NormalRefinement< NormalT >::getCorrespondences ( std::vector< std::vector< int > > &  k_indices,
std::vector< std::vector< float > > &  k_sqr_distances 
)
inline

Get correspondences (copy)

Parameters
k_indicesindices of neighboring points
k_sqr_distancessquared distances to the neighboring points

Definition at line 238 of file normal_refinement.h.

template<typename NormalT>
unsigned int pcl::NormalRefinement< NormalT >::getMaxIterations ( )
inline

Get maximum iterations.

Returns
maximum iterations

Definition at line 257 of file normal_refinement.h.

template<typename NormalT>
void pcl::NormalRefinement< NormalT >::setConvergenceThreshold ( float  convergence_threshold)
inline

Set convergence threshold.

Parameters
convergence_thresholdconvergence threshold

Definition at line 266 of file normal_refinement.h.

Referenced by pcl::NormalRefinement< NormalT >::NormalRefinement().

template<typename NormalT>
void pcl::NormalRefinement< NormalT >::setCorrespondences ( const std::vector< std::vector< int > > &  k_indices,
const std::vector< std::vector< float > > &  k_sqr_distances 
)
inline

Set correspondences calculated from nearest neighbor search.

Parameters
k_indicesindices of neighboring points
k_sqr_distancessquared distances to the neighboring points

Definition at line 227 of file normal_refinement.h.

Referenced by pcl::NormalRefinement< NormalT >::NormalRefinement().

template<typename NormalT>
void pcl::NormalRefinement< NormalT >::setMaxIterations ( unsigned int  max_iterations)
inline

Set maximum iterations.

Parameters
max_iterationsmaximum iterations

Definition at line 248 of file normal_refinement.h.

Referenced by pcl::NormalRefinement< NormalT >::NormalRefinement().


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