43 #include <pcl/features/principal_curvatures.h>
45 #include <pcl/common/point_tests.h>
48 template <
typename Po
intInT,
typename Po
intNT,
typename Po
intOutT>
void
53 threads_ = omp_get_num_procs();
55 threads_ = nr_threads;
56 PCL_DEBUG (
"[pcl::PrincipalCurvaturesEstimation::setNumberOfThreads] Setting number of threads to %u.\n", threads_);
60 PCL_WARN (
"[pcl::PrincipalCurvaturesEstimation::setNumberOfThreads] Parallelization is requested, but OpenMP is not available! Continuing without parallelization.\n");
65 template <
typename Po
intInT,
typename Po
intNT,
typename Po
intOutT>
void
68 float &pcx,
float &pcy,
float &pcz,
float &pc1,
float &pc2)
70 const auto n_idx = normals[p_idx].getNormalVector3fMap();
71 EIGEN_ALIGN16
const Eigen::Matrix3f I = Eigen::Matrix3f::Identity ();
72 EIGEN_ALIGN16
const Eigen::Matrix3f M = I - n_idx * n_idx.transpose ();
75 std::vector<Eigen::Vector3f, Eigen::aligned_allocator<Eigen::Vector3f> > projected_normals (indices.size());
76 Eigen::Vector3f xyz_centroid = Eigen::Vector3f::Zero();
77 for (std::size_t idx = 0; idx < indices.size(); ++idx)
79 const auto normal = normals[indices[idx]].getNormalVector3fMap();
80 projected_normals[idx] = M * normal;
81 xyz_centroid += projected_normals[idx];
85 xyz_centroid /=
static_cast<float> (indices.size ());
88 EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix = Eigen::Matrix3f::Zero();
91 for (std::size_t idx = 0; idx < indices.size (); ++idx)
93 const Eigen::Vector3f demean = projected_normals[idx] - xyz_centroid;
95 const double demean_xy = demean[0] * demean[1];
96 const double demean_xz = demean[0] * demean[2];
97 const double demean_yz = demean[1] * demean[2];
99 covariance_matrix(0, 0) += demean[0] * demean[0];
100 covariance_matrix(0, 1) +=
static_cast<float> (demean_xy);
101 covariance_matrix(0, 2) +=
static_cast<float> (demean_xz);
103 covariance_matrix(1, 0) +=
static_cast<float> (demean_xy);
104 covariance_matrix(1, 1) += demean[1] * demean[1];
105 covariance_matrix(1, 2) +=
static_cast<float> (demean_yz);
107 covariance_matrix(2, 0) +=
static_cast<float> (demean_xz);
108 covariance_matrix(2, 1) +=
static_cast<float> (demean_yz);
109 covariance_matrix(2, 2) += demean[2] * demean[2];
113 Eigen::Vector3f eigenvalues;
114 Eigen::Vector3f eigenvector;
118 pcx = eigenvector [0];
119 pcy = eigenvector [1];
120 pcz = eigenvector [2];
121 const float indices_size = 1.0f /
static_cast<float> (indices.size ());
122 pc1 = eigenvalues [2] * indices_size;
123 pc2 = eigenvalues [1] * indices_size;
128 template <
typename Po
intInT,
typename Po
intNT,
typename Po
intOutT>
void
134 std::vector<float> nn_dists (k_);
138 if (input_->is_dense)
140 #pragma omp parallel for \
143 firstprivate(nn_indices, nn_dists) \
144 num_threads(threads_) \
145 schedule(dynamic, chunk_size_)
147 for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t> (indices_->size ()); ++idx)
149 if (this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
151 output[idx].principal_curvature[0] = output[idx].principal_curvature[1] = output[idx].principal_curvature[2] =
152 output[idx].pc1 = output[idx].pc2 = std::numeric_limits<float>::quiet_NaN ();
158 computePointPrincipalCurvatures (*normals_, (*indices_)[idx], nn_indices,
159 output[idx].principal_curvature[0], output[idx].principal_curvature[1], output[idx].principal_curvature[2],
160 output[idx].pc1, output[idx].pc2);
165 #pragma omp parallel for \
168 firstprivate(nn_indices, nn_dists) \
169 num_threads(threads_) \
170 schedule(dynamic, chunk_size_)
172 for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t> (indices_->size ()); ++idx)
174 if (!
isFinite ((*input_)[(*indices_)[idx]]) ||
175 this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
177 output[idx].principal_curvature[0] = output[idx].principal_curvature[1] = output[idx].principal_curvature[2] =
178 output[idx].pc1 = output[idx].pc2 = std::numeric_limits<float>::quiet_NaN ();
184 computePointPrincipalCurvatures (*normals_, (*indices_)[idx], nn_indices,
185 output[idx].principal_curvature[0], output[idx].principal_curvature[1], output[idx].principal_curvature[2],
186 output[idx].pc1, output[idx].pc2);
191 #define PCL_INSTANTIATE_PrincipalCurvaturesEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::PrincipalCurvaturesEstimation<T,NT,OutT>;
bool is_dense
True if no points are invalid (e.g., have NaN or Inf values in any of their floating point fields).
void setNumberOfThreads(unsigned int nr_threads)
Initialize the scheduler and set the number of threads to use.
void computePointPrincipalCurvatures(const pcl::PointCloud< PointNT > &normals, int p_idx, const pcl::Indices &indices, float &pcx, float &pcy, float &pcz, float &pc1, float &pc2)
Perform Principal Components Analysis (PCA) on the point normals of a surface patch in the tangent pl...
void computeFeature(PointCloudOut &output) override
Estimate the principal curvature (eigenvector of the max eigenvalue), along with both the max (pc1) a...
void computeCorrespondingEigenVector(const Matrix &mat, const typename Matrix::Scalar &eigenvalue, Vector &eigenvector)
determines the corresponding eigenvector to the given eigenvalue of the symmetric positive semi defin...
void eigen33(const Matrix &mat, typename Matrix::Scalar &eigenvalue, Vector &eigenvector)
determines the eigenvector and eigenvalue of the smallest eigenvalue of the symmetric positive semi d...
bool isFinite(const PointT &pt)
Tests if the 3D components of a point are all finite param[in] pt point to be tested return true if f...
IndicesAllocator<> Indices
Type used for indices in PCL.