SamplingSurfaceNormal divides the input space into grids until each grid contains a maximum of N points, and samples points randomly within each grid. Normal is computed using the N points of each grid. All points sampled within a grid are assigned the same normal. More...
#include <sampling_surface_normal.h>
Classes | |
struct | CompareDim |
CompareDim is a comparator object for sorting across a specific dimenstion (i,.e X, Y or Z) More... | |
Public Types | |
typedef boost::shared_ptr < const SamplingSurfaceNormal < PointT > > | ConstPtr |
typedef boost::shared_ptr < SamplingSurfaceNormal < PointT > > | Ptr |
Public Member Functions | |
float | getRatio () const |
Get the value of the internal ratio parameter. | |
unsigned int | getSample () const |
Get the value of the internal sample parameter. | |
unsigned int | getSeed () const |
Get the value of the internal seed parameter. | |
SamplingSurfaceNormal () | |
Empty constructor. | |
void | setRatio (float ratio) |
Set ratio of points to be sampled in each grid. | |
void | setSample (unsigned int sample) |
Set maximum number of samples in each grid. | |
void | setSeed (unsigned int seed) |
Set seed of random function. | |
Protected Member Functions | |
void | applyFilter (PointCloud &output) |
Sample of point indices into a separate PointCloud. | |
Protected Attributes | |
float | ratio_ |
Ratio of points to be sampled in each grid. | |
unsigned int | sample_ |
Maximum number of samples in each grid. | |
unsigned int | seed_ |
Random number seed. | |
Private Types | |
typedef Filter< PointT > ::PointCloud | PointCloud |
typedef PointCloud::ConstPtr | PointCloudConstPtr |
typedef PointCloud::Ptr | PointCloudPtr |
typedef Eigen::Matrix< float, Eigen::Dynamic, 1 > | Vector |
Private Member Functions | |
unsigned int | computeMeanAndCovarianceMatrix (const pcl::PointCloud< PointT > &cloud, Eigen::Matrix3f &covariance_matrix, Eigen::Vector4f ¢roid) |
Computes the covariance matrix for points in the cloud. This is a port from features to avoid features dependency for filters. | |
void | computeNormal (const PointCloud &cloud, Eigen::Vector4f &normal, float &curvature) |
Computes the normal for points in a grid. This is a port from features to avoid features dependency for filters. | |
float | findCutVal (const PointCloud &cloud, const int cut_dim, const int cut_index) |
Returns the threshold for splitting in a given dimension. | |
void | findXYZMaxMin (const PointCloud &cloud, Vector &max_vec, Vector &min_vec) |
Finds the max and min values in each dimension. | |
void | partition (const PointCloud &cloud, const int first, const int last, const Vector min_values, const Vector max_values, std::vector< int > &indices, PointCloud &outcloud) |
Recursively partition the point cloud, stopping when each grid contains less than sample_ points Points are randomly sampled when a grid is found. | |
void | samplePartition (const PointCloud &data, const int first, const int last, std::vector< int > &indices, PointCloud &outcloud) |
Randomly sample the points in each grid. | |
void | solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix, float &nx, float &ny, float &nz, float &curvature) |
Solve the eigenvalues and eigenvectors of a given 3x3 covariance matrix, and estimate the least-squares plane normal and surface curvature. |
SamplingSurfaceNormal divides the input space into grids until each grid contains a maximum of N points, and samples points randomly within each grid. Normal is computed using the N points of each grid. All points sampled within a grid are assigned the same normal.
Definition at line 55 of file sampling_surface_normal.h.
typedef boost::shared_ptr< const SamplingSurfaceNormal<PointT> > pcl::SamplingSurfaceNormal< PointT >::ConstPtr |
Reimplemented from pcl::Filter< PointT >.
Definition at line 71 of file sampling_surface_normal.h.
typedef Filter<PointT>::PointCloud pcl::SamplingSurfaceNormal< PointT >::PointCloud [private] |
Reimplemented from pcl::Filter< PointT >.
Definition at line 62 of file sampling_surface_normal.h.
typedef PointCloud::ConstPtr pcl::SamplingSurfaceNormal< PointT >::PointCloudConstPtr [private] |
Reimplemented from pcl::Filter< PointT >.
Definition at line 64 of file sampling_surface_normal.h.
typedef PointCloud::Ptr pcl::SamplingSurfaceNormal< PointT >::PointCloudPtr [private] |
Reimplemented from pcl::Filter< PointT >.
Definition at line 63 of file sampling_surface_normal.h.
typedef boost::shared_ptr< SamplingSurfaceNormal<PointT> > pcl::SamplingSurfaceNormal< PointT >::Ptr |
Reimplemented from pcl::Filter< PointT >.
Definition at line 70 of file sampling_surface_normal.h.
typedef Eigen::Matrix<float, Eigen::Dynamic, 1> pcl::SamplingSurfaceNormal< PointT >::Vector [private] |
Definition at line 66 of file sampling_surface_normal.h.
pcl::SamplingSurfaceNormal< PointT >::SamplingSurfaceNormal | ( | ) | [inline] |
Empty constructor.
Definition at line 74 of file sampling_surface_normal.h.
void pcl::SamplingSurfaceNormal< PointT >::applyFilter | ( | PointCloud & | output | ) | [protected, virtual] |
Sample of point indices into a separate PointCloud.
[out] | output | the resultant point cloud |
Implements pcl::Filter< PointT >.
Definition at line 48 of file sampling_surface_normal.hpp.
unsigned int pcl::SamplingSurfaceNormal< PointT >::computeMeanAndCovarianceMatrix | ( | const pcl::PointCloud< PointT > & | cloud, |
Eigen::Matrix3f & | covariance_matrix, | ||
Eigen::Vector4f & | centroid | ||
) | [inline, private] |
Computes the covariance matrix for points in the cloud. This is a port from features to avoid features dependency for filters.
[in] | cloud | The input cloud |
[out] | covariance_matrix | the covariance matrix |
[out] | centroid | the centroid |
Definition at line 231 of file sampling_surface_normal.hpp.
void pcl::SamplingSurfaceNormal< PointT >::computeNormal | ( | const PointCloud & | cloud, |
Eigen::Vector4f & | normal, | ||
float & | curvature | ||
) | [private] |
Computes the normal for points in a grid. This is a port from features to avoid features dependency for filters.
[in] | cloud | The input cloud |
[out] | normal | the computed normal |
[out] | curvature | the computed curvature |
Definition at line 204 of file sampling_surface_normal.hpp.
float pcl::SamplingSurfaceNormal< PointT >::findCutVal | ( | const PointCloud & | cloud, |
const int | cut_dim, | ||
const int | cut_index | ||
) | [private] |
Returns the threshold for splitting in a given dimension.
[in] | cloud | the input cloud |
[in] | cut_dim | the input dimension (0=x, 1=y, 2=z) |
[in] | cut_index | the input index in the cloud |
Definition at line 297 of file sampling_surface_normal.hpp.
void pcl::SamplingSurfaceNormal< PointT >::findXYZMaxMin | ( | const PointCloud & | cloud, |
Vector & | max_vec, | ||
Vector & | min_vec | ||
) | [private] |
Finds the max and min values in each dimension.
[in] | cloud | the input cloud |
[out] | max_vec | the max value vector |
[out] | min_vec | the min value vector |
Definition at line 66 of file sampling_surface_normal.hpp.
float pcl::SamplingSurfaceNormal< PointT >::getRatio | ( | ) | const [inline] |
Get the value of the internal ratio parameter.
Definition at line 125 of file sampling_surface_normal.h.
unsigned int pcl::SamplingSurfaceNormal< PointT >::getSample | ( | ) | const [inline] |
Get the value of the internal sample parameter.
Definition at line 92 of file sampling_surface_normal.h.
unsigned int pcl::SamplingSurfaceNormal< PointT >::getSeed | ( | ) | const [inline] |
Get the value of the internal seed parameter.
Definition at line 109 of file sampling_surface_normal.h.
void pcl::SamplingSurfaceNormal< PointT >::partition | ( | const PointCloud & | cloud, |
const int | first, | ||
const int | last, | ||
const Vector | min_values, | ||
const Vector | max_values, | ||
std::vector< int > & | indices, | ||
PointCloud & | outcloud | ||
) | [private] |
Recursively partition the point cloud, stopping when each grid contains less than sample_ points Points are randomly sampled when a grid is found.
cloud | ||
first | ||
last | ||
min_values | ||
max_values | ||
indices | ||
[out] | outcloud | output the resultant point cloud |
Definition at line 122 of file sampling_surface_normal.hpp.
void pcl::SamplingSurfaceNormal< PointT >::samplePartition | ( | const PointCloud & | data, |
const int | first, | ||
const int | last, | ||
std::vector< int > & | indices, | ||
PointCloud & | outcloud | ||
) | [private] |
Randomly sample the points in each grid.
[in] | data | |
[in] | first | |
[in] | last | |
[out] | indices | |
[out] | output | the resultant point cloud |
Definition at line 161 of file sampling_surface_normal.hpp.
void pcl::SamplingSurfaceNormal< PointT >::setRatio | ( | float | ratio | ) | [inline] |
Set ratio of points to be sampled in each grid.
[in] | ratio | sample the ratio of points to be sampled in each grid |
Definition at line 118 of file sampling_surface_normal.h.
void pcl::SamplingSurfaceNormal< PointT >::setSample | ( | unsigned int | sample | ) | [inline] |
Set maximum number of samples in each grid.
[in] | sample | maximum number of samples in each grid |
Definition at line 85 of file sampling_surface_normal.h.
void pcl::SamplingSurfaceNormal< PointT >::setSeed | ( | unsigned int | seed | ) | [inline] |
Set seed of random function.
[in] | seed | the input seed |
Definition at line 101 of file sampling_surface_normal.h.
void pcl::SamplingSurfaceNormal< PointT >::solvePlaneParameters | ( | const Eigen::Matrix3f & | covariance_matrix, |
float & | nx, | ||
float & | ny, | ||
float & | nz, | ||
float & | curvature | ||
) | [private] |
Solve the eigenvalues and eigenvectors of a given 3x3 covariance matrix, and estimate the least-squares plane normal and surface curvature.
[in] | covariance_matrix | the 3x3 covariance matrix |
[out] | (nx | ny nz) plane_parameters the resultant plane parameters as: a, b, c, d (ax + by + cz + d = 0) |
[out] | curvature | the estimated surface curvature as a measure of |
Definition at line 275 of file sampling_surface_normal.hpp.
float pcl::SamplingSurfaceNormal< PointT >::ratio_ [protected] |
Ratio of points to be sampled in each grid.
Definition at line 137 of file sampling_surface_normal.h.
unsigned int pcl::SamplingSurfaceNormal< PointT >::sample_ [protected] |
Maximum number of samples in each grid.
Definition at line 133 of file sampling_surface_normal.h.
unsigned int pcl::SamplingSurfaceNormal< PointT >::seed_ [protected] |
Random number seed.
Definition at line 135 of file sampling_surface_normal.h.