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>
|
void | computeFeature (const Eigen::MatrixXd &samples, PointCloudOut &output) |
| Estimate the curvature for a set of point neighborhoods with given centroids. More...
|
|
| CurvatureEstimationTaubin (unsigned int num_threads=0) |
| Constructor. Set the number of threads to use. More...
|
|
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. More...
|
|
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. More...
|
|
std::vector< int > const & | getNeighborhoodCentroids () const |
| Get the centroid indices of each point neighborhood. More...
|
|
std::vector< std::vector< int > > const & | getNeighborhoods () const |
| Get the indices of each point neighborhood. More...
|
|
void | setNumSamples (int num_samples) |
| Set the number of samples (point neighborhoods). More...
|
|
void | setNumThreads (int num_threads) |
| Set the number of threads used for parallelizing Taubin Quadric Fitting. More...
|
|
|
static bool | isSecondElementSmaller (const std::vector< double > &p1, const std::vector< double > &p2) |
| Compares two vectors by looking at their second elements. More...
|
|
|
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. More...
|
|
|
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. More...
|
|
int | sign (double x) |
| Get the sign of a given value (according to the sign function). More...
|
|
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. More...
|
|
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. More...
|
|
template<typename PointInT, typename PointOutT>
class pcl::CurvatureEstimationTaubin< PointInT, PointOutT >
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.
- Author
- Andreas ten Pas
Definition at line 99 of file curvature_estimation_taubin.h.
template<typename PointInT, typename PointOutT>
template<typename PointInT, typename PointOutT>
Constructor. Set the number of threads to use.
- Parameters
-
num_threads | the number of threads to use (0: automatic) |
Definition at line 115 of file curvature_estimation_taubin.h.
template<typename PointInT , typename PointOutT >
Estimate the curvature for a set of point neighborhoods with given centroids.
- Parameters
-
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.
template<typename PointInT , typename PointOutT >
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.
- Note
- If <setIndices()> is used, the set of indices is not randomly selected.
- Parameters
-
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.
template<typename PointInT , typename PointOutT >
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.
- Parameters
-
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.
template<typename PointInT, typename PointOutT>
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.
- Parameters
-
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.
template<typename PointInT, typename PointOutT>
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.
- Parameters
-
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.
template<typename PointInT, typename PointOutT>
template<typename PointInT, typename PointOutT>
template<typename PointInT, typename PointOutT>
static bool pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::isSecondElementSmaller |
( |
const std::vector< double > & |
p1, |
|
|
const std::vector< double > & |
p2 |
|
) |
| |
|
inlinestatic |
Compares two vectors by looking at their second elements.
- Parameters
-
p1 | the first vector to compare |
p2 | the second vector to compare |
Definition at line 278 of file curvature_estimation_taubin.h.
template<typename PointInT, typename PointOutT>
template<typename PointInT, typename PointOutT>
Set the number of threads used for parallelizing Taubin Quadric Fitting.
- Parameters
-
num_samples | the number of samples |
Definition at line 419 of file curvature_estimation_taubin.h.
template<typename PointInT, typename PointOutT>
template<typename PointInT, typename PointOutT>
bool pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::solveGeneralizedEigenProblem |
( |
const Eigen::MatrixXd & |
A, |
|
|
const Eigen::MatrixXd & |
B, |
|
|
Eigen::MatrixXd & |
v, |
|
|
Eigen::MatrixXd & |
lambda |
|
) |
| |
|
inlineprivate |
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.
- Parameters
-
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.
template<typename PointInT, typename PointOutT>
void pcl::CurvatureEstimationTaubin< PointInT, PointOutT >::unpackQuadric |
( |
const Eigen::VectorXd & |
quadric_parameters, |
|
|
Eigen::Vector3d & |
quadric_centroid, |
|
|
Eigen::Matrix3d & |
quadric_covariance_matrix |
|
) |
| |
|
inlineprivate |
Unpack the quadric, using its parameters, and return the centroid and the covariance matrix of the quadric.
- Parameters
-
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.
template<typename PointInT, typename PointOutT>
template<typename PointInT, typename PointOutT>
template<typename PointInT, typename PointOutT>
template<typename PointInT, typename PointOutT>
template<typename PointInT, typename PointOutT>
template<typename PointInT, typename PointOutT>
The documentation for this class was generated from the following files: