Normal vector refinement class More...
#include <normal_refinement.h>
Public Member Functions | |
float | getConvergenceThreshold () |
Get convergence threshold. | |
void | getCorrespondences (std::vector< std::vector< int > > &k_indices, std::vector< std::vector< float > > &k_sqr_distances) |
Get correspondences (copy) | |
unsigned int | getMaxIterations () |
Get maximum iterations. | |
NormalRefinement () | |
Empty constructor, sets default convergence parameters. | |
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. | |
void | setConvergenceThreshold (float convergence_threshold) |
Set convergence threshold. | |
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. | |
void | setMaxIterations (unsigned int max_iterations) |
Set maximum iterations. | |
Protected Member Functions | |
void | applyFilter (PointCloud &output) |
Filter a Point Cloud. | |
Private Types | |
typedef Filter< NormalT > ::PointCloud | PointCloud |
typedef PointCloud::ConstPtr | PointCloudConstPtr |
typedef PointCloud::Ptr | PointCloudPtr |
Private Attributes | |
float | convergence_threshold_ |
Convergence threshold in the interval [0,1] on the mean of 1 - dot products between previous iteration and the current. | |
std::vector< std::vector< int > > | k_indices_ |
indices of neighboring points | |
std::vector< std::vector< float > > | k_sqr_distances_ |
squared distances to the neighboring points | |
unsigned int | max_iterations_ |
Maximum allowable iterations over the whole point cloud for refinement. |
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.
Usage example:
// Input point cloud pcl::PointCloud<PointT> cloud; // Fill cloud... // Estimated and refined normals pcl::PointCloud<NormalT> 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 pcl::search::KdTree<pcl::PointXYZRGB> search; search.setInputCloud (cloud.makeShared ()); search.nearestKSearch (cloud, std::vector<int> (), k, k_indices, k_sqr_distances); // Use search results for normal estimation pcl::NormalEstimation<PointT, NormalT> ne; 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); pcl::flipNormalTowardsViewpoint (cloud[i], cloud.sensor_origin_[0], cloud.sensor_origin_[1], cloud.sensor_origin_[2], 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);
Definition at line 188 of file normal_refinement.h.
typedef Filter<NormalT>::PointCloud pcl::NormalRefinement< NormalT >::PointCloud [private] |
Reimplemented from pcl::Filter< NormalT >.
Definition at line 194 of file normal_refinement.h.
typedef PointCloud::ConstPtr pcl::NormalRefinement< NormalT >::PointCloudConstPtr [private] |
Reimplemented from pcl::Filter< NormalT >.
Definition at line 196 of file normal_refinement.h.
typedef PointCloud::Ptr pcl::NormalRefinement< NormalT >::PointCloudPtr [private] |
Reimplemented from pcl::Filter< NormalT >.
Definition at line 195 of file normal_refinement.h.
pcl::NormalRefinement< NormalT >::NormalRefinement | ( | ) | [inline] |
Empty constructor, sets default convergence parameters.
Definition at line 201 of file normal_refinement.h.
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.
k_indices | indices of neighboring points |
k_sqr_distances | squared distances to the neighboring points |
Definition at line 213 of file normal_refinement.h.
void pcl::NormalRefinement< NormalT >::applyFilter | ( | PointCloud & | output | ) | [protected] |
output | the resultant point cloud message |
Definition at line 48 of file normal_refinement.hpp.
float pcl::NormalRefinement< NormalT >::getConvergenceThreshold | ( | ) | [inline] |
Get convergence threshold.
Definition at line 275 of file normal_refinement.h.
void pcl::NormalRefinement< NormalT >::getCorrespondences | ( | std::vector< std::vector< int > > & | k_indices, |
std::vector< std::vector< float > > & | k_sqr_distances | ||
) | [inline] |
Get correspondences (copy)
k_indices | indices of neighboring points |
k_sqr_distances | squared distances to the neighboring points |
Definition at line 238 of file normal_refinement.h.
unsigned int pcl::NormalRefinement< NormalT >::getMaxIterations | ( | ) | [inline] |
Get maximum iterations.
Definition at line 257 of file normal_refinement.h.
void pcl::NormalRefinement< NormalT >::setConvergenceThreshold | ( | float | convergence_threshold | ) | [inline] |
Set convergence threshold.
convergence_threshold | convergence threshold |
Definition at line 266 of file normal_refinement.h.
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.
k_indices | indices of neighboring points |
k_sqr_distances | squared distances to the neighboring points |
Definition at line 227 of file normal_refinement.h.
void pcl::NormalRefinement< NormalT >::setMaxIterations | ( | unsigned int | max_iterations | ) | [inline] |
Set maximum iterations.
max_iterations | maximum iterations |
Definition at line 248 of file normal_refinement.h.
float pcl::NormalRefinement< NormalT >::convergence_threshold_ [private] |
Convergence threshold in the interval [0,1] on the mean of 1 - dot products between previous iteration and the current.
Definition at line 298 of file normal_refinement.h.
std::vector< std::vector<int> > pcl::NormalRefinement< NormalT >::k_indices_ [private] |
indices of neighboring points
Definition at line 289 of file normal_refinement.h.
std::vector< std::vector<float> > pcl::NormalRefinement< NormalT >::k_sqr_distances_ [private] |
squared distances to the neighboring points
Definition at line 292 of file normal_refinement.h.
unsigned int pcl::NormalRefinement< NormalT >::max_iterations_ [private] |
Maximum allowable iterations over the whole point cloud for refinement.
Definition at line 295 of file normal_refinement.h.