CurvatureEstimationTaubin estimates the curvature for a set of point neighborhoods in the cloud using Taubin Quadric Fitting. This class uses the OpenMP standard to permit parallelized feature computation. More...
#include <curvature_estimation_taubin.h>
Public Types | |
typedef Feature< PointInT, PointOutT >::PointCloudOut | PointCloudOut |
Public Member Functions | |
void | computeFeature (const Eigen::MatrixXd &samples, PointCloudOut &output) |
Estimate the curvature for a set of point neighborhoods with given centroids. | |
CurvatureEstimationTaubin (unsigned int num_threads=0) | |
Constructor. Set the number of threads to use. | |
void | estimateMedianCurvature (const std::vector< int > &indices, const Eigen::VectorXd &quadric_parameters, double &median_curvature, Eigen::Vector3d &normal, Eigen::Vector3d &curvature_axis, Eigen::Vector3d &curvature_centroid, bool is_deterministic=false) |
Estimate the median curvature for a given quadric, using the indices of the point neighborhood that the quadric is fitted to and its parameters, and return the estimated curvature, the normal axis, the curvature axis, and the curvature centroid. | |
void | fitQuadric (const std::vector< int > &indices, Eigen::VectorXd &quadric_parameters, Eigen::Vector3d &quadric_centroid, Eigen::Matrix3d &quadric_covariance_matrix) |
Fit a quadric to a given set of points, using their indices, and return the parameters of the quadric in implicit form, its centroid, and its covariance matrix. This method uses Taubin Quadric Fitting. | |
std::vector< int > const & | getNeighborhoodCentroids () const |
Get the centroid indices of each point neighborhood. | |
std::vector< std::vector< int > > const & | getNeighborhoods () const |
Get the indices of each point neighborhood. | |
void | setNumSamples (int num_samples) |
Set the number of samples (point neighborhoods). | |
void | setNumThreads (int num_threads) |
Set the number of threads used for parallelizing Taubin Quadric Fitting. | |
Static Public Member Functions | |
static bool | isSecondElementSmaller (const std::vector< double > &p1, const std::vector< double > &p2) |
Compares two vectors by looking at their second elements. | |
Protected Member Functions | |
void | computeFeature (PointCloudOut &output) |
Estimate the curvature for a set of point neighborhoods sampled from the cloud given by <setInputCloud()>, using the spatial locator in setSearchMethod(). This method creates its own set of randomly selected indices. | |
Private Member Functions | |
void | computeFeature (const std::vector< int > &nn_indices, int index, PointCloudOut &output) |
Estimate the curvature for a set of points, using their indices and the index of the neighborhood's centroid, and updates the output point cloud. | |
int | sign (double x) |
Get the sign of a given value (according to the sign function). | |
bool | solveGeneralizedEigenProblem (const Eigen::MatrixXd &A, const Eigen::MatrixXd &B, Eigen::MatrixXd &v, Eigen::MatrixXd &lambda) |
Solves the generalized Eigen problem A * v(j) = lambda(j) * B * v(j), where v are the Eigen vectors, and lambda are the Eigen values. The eigenvalues are stored as: (lambda(:, 1) + lambda(:, 2)*i)./lambda(:, 3). This method returns true if the Eigen problem is solved successfully. | |
void | unpackQuadric (const Eigen::VectorXd &quadric_parameters, Eigen::Vector3d &quadric_centroid, Eigen::Matrix3d &quadric_covariance_matrix) |
Unpack the quadric, using its parameters, and return the centroid and the covariance matrix of the quadric. | |
Private Attributes | |
std::vector< int > | neighborhood_centroids_ |
std::vector< std::vector< int > > | neighborhoods_ |
unsigned int | num_samples_ |
unsigned int | num_threads_ |
double | time_curvature |
double | time_taubin |
CurvatureEstimationTaubin estimates the curvature for a set of point neighborhoods in the cloud using Taubin Quadric Fitting. This class uses the OpenMP standard to permit parallelized feature computation.
Definition at line 99 of file curvature_estimation_taubin.h.
typedef Feature<PointInT, PointOutT>::PointCloudOut pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::PointCloudOut |
Definition at line 110 of file curvature_estimation_taubin.h.
pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::CurvatureEstimationTaubin | ( | unsigned int | num_threads = 0 | ) | [inline] |
Constructor. Set the number of threads to use.
num_threads | the number of threads to use (0: automatic) |
Definition at line 115 of file curvature_estimation_taubin.h.
void pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::computeFeature | ( | const Eigen::MatrixXd & | samples, |
PointCloudOut & | output | ||
) |
Estimate the curvature for a set of point neighborhoods with given centroids.
samples | the centroids of the neighborhoods |
output | the resultant point cloud that contains the curvature, normal axes, curvature axes, and curvature centroids |
Definition at line 6 of file curvature_estimation_taubin.hpp.
void pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::computeFeature | ( | PointCloudOut & | output | ) | [protected] |
Estimate the curvature for a set of point neighborhoods sampled from the cloud given by <setInputCloud()>, using the spatial locator in setSearchMethod(). This method creates its own set of randomly selected indices.
output | the resultant point cloud that contains the curvature, normal axes, curvature axes, and curvature centroids |
Definition at line 129 of file curvature_estimation_taubin.hpp.
void pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::computeFeature | ( | const std::vector< int > & | nn_indices, |
int | index, | ||
PointCloudOut & | output | ||
) | [private] |
Estimate the curvature for a set of points, using their indices and the index of the neighborhood's centroid, and updates the output point cloud.
output | the resultant point cloud that contains the curvature, normal axes, curvature axes, and curvature centroids |
Definition at line 212 of file curvature_estimation_taubin.hpp.
void pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::estimateMedianCurvature | ( | const std::vector< int > & | indices, |
const Eigen::VectorXd & | quadric_parameters, | ||
double & | median_curvature, | ||
Eigen::Vector3d & | normal, | ||
Eigen::Vector3d & | curvature_axis, | ||
Eigen::Vector3d & | curvature_centroid, | ||
bool | is_deterministic = false |
||
) | [inline] |
Estimate the median curvature for a given quadric, using the indices of the point neighborhood that the quadric is fitted to and its parameters, and return the estimated curvature, the normal axis, the curvature axis, and the curvature centroid.
indices | the point cloud indices of the points |
quadric_parameters | the quadric parameters as: a, b, c, d, e, f, g, h, i, j (ax^2 + by^2 + cz^2 + dxy + eyz + fxz + gx + hy + iz + j = 0) |
median_curvature | the resultant, estimated median curvature of the quadric |
normal | the normal axis of the quadric (direction vector) |
curvature_axis | the curvature axis of the quadric (direction vector) |
curvature_centroid | the centroid of curvature |
Definition at line 294 of file curvature_estimation_taubin.h.
void pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::fitQuadric | ( | const std::vector< int > & | indices, |
Eigen::VectorXd & | quadric_parameters, | ||
Eigen::Vector3d & | quadric_centroid, | ||
Eigen::Matrix3d & | quadric_covariance_matrix | ||
) | [inline] |
Fit a quadric to a given set of points, using their indices, and return the parameters of the quadric in implicit form, its centroid, and its covariance matrix. This method uses Taubin Quadric Fitting.
indices | the point cloud indices of the points |
quadric_parameters | the resultant quadric parameters as: a, b, c, d, e, f, g, h, i, j (ax^2 + by^2 + cz^2 + dxy + eyz + fxz + gx + hy + iz + j = 0) |
quadric_centroid | the resultant centroid of the quadric |
quadric_covariance_matrix | the resultant covariance matrix of the quadric |
Definition at line 130 of file curvature_estimation_taubin.h.
std::vector<int> const& pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::getNeighborhoodCentroids | ( | ) | const [inline] |
Get the centroid indices of each point neighborhood.
Definition at line 434 of file curvature_estimation_taubin.h.
std::vector<std::vector<int> > const& pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::getNeighborhoods | ( | ) | const [inline] |
Get the indices of each point neighborhood.
Definition at line 426 of file curvature_estimation_taubin.h.
static bool pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::isSecondElementSmaller | ( | const std::vector< double > & | p1, |
const std::vector< double > & | p2 | ||
) | [inline, static] |
Compares two vectors by looking at their second elements.
p1 | the first vector to compare |
p2 | the second vector to compare |
Definition at line 278 of file curvature_estimation_taubin.h.
void pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::setNumSamples | ( | int | num_samples | ) | [inline] |
Set the number of samples (point neighborhoods).
num_samples | the number of samples |
Definition at line 411 of file curvature_estimation_taubin.h.
void pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::setNumThreads | ( | int | num_threads | ) | [inline] |
Set the number of threads used for parallelizing Taubin Quadric Fitting.
num_samples | the number of samples |
Definition at line 419 of file curvature_estimation_taubin.h.
int pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::sign | ( | double | x | ) | [inline, private] |
Get the sign of a given value (according to the sign function).
x | the given value |
Definition at line 504 of file curvature_estimation_taubin.h.
bool pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::solveGeneralizedEigenProblem | ( | const Eigen::MatrixXd & | A, |
const Eigen::MatrixXd & | B, | ||
Eigen::MatrixXd & | v, | ||
Eigen::MatrixXd & | lambda | ||
) | [inline, private] |
Solves the generalized Eigen problem A * v(j) = lambda(j) * B * v(j), where v are the Eigen vectors, and lambda are the Eigen values. The eigenvalues are stored as: (lambda(:, 1) + lambda(:, 2)*i)./lambda(:, 3). This method returns true if the Eigen problem is solved successfully.
A | the matrix A in the problem |
B | the matrix B in the problem |
v | the resultant Eigen vectors |
lambda | the resultant Eigen vectors (see above) |
Definition at line 522 of file curvature_estimation_taubin.h.
void pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::unpackQuadric | ( | const Eigen::VectorXd & | quadric_parameters, |
Eigen::Vector3d & | quadric_centroid, | ||
Eigen::Matrix3d & | quadric_covariance_matrix | ||
) | [inline, private] |
Unpack the quadric, using its parameters, and return the centroid and the covariance matrix of the quadric.
quadric_parameters | the resultant quadric parameters as: a, b, c, d, e, f, g, h, i, j (ax^2 + by^2 + cz^2 + dxy + eyz + fxz + gx + hy + iz + j = 0) |
quadric_centroid | the resultant centroid of the quadric |
quadric_covariance_matrix | the resultant covariance matrix of the quadric |
Definition at line 477 of file curvature_estimation_taubin.h.
std::vector<int> pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::neighborhood_centroids_ [private] |
Definition at line 561 of file curvature_estimation_taubin.h.
std::vector<std::vector<int> > pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::neighborhoods_ [private] |
Definition at line 560 of file curvature_estimation_taubin.h.
unsigned int pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::num_samples_ [private] |
Definition at line 556 of file curvature_estimation_taubin.h.
unsigned int pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::num_threads_ [private] |
Definition at line 559 of file curvature_estimation_taubin.h.
double pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::time_curvature [private] |
Definition at line 563 of file curvature_estimation_taubin.h.
double pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::time_taubin [private] |
Definition at line 562 of file curvature_estimation_taubin.h.