Point Cloud Library (PCL)  1.14.1-dev
principal_curvatures.hpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2011, Willow Garage, Inc.
6  * Copyright (c) 2012-, Open Perception, Inc.
7  *
8  * All rights reserved.
9  *
10  * Redistribution and use in source and binary forms, with or without
11  * modification, are permitted provided that the following conditions
12  * are met:
13  *
14  * * Redistributions of source code must retain the above copyright
15  * notice, this list of conditions and the following disclaimer.
16  * * Redistributions in binary form must reproduce the above
17  * copyright notice, this list of conditions and the following
18  * disclaimer in the documentation and/or other materials provided
19  * with the distribution.
20  * * Neither the name of the copyright holder(s) nor the names of its
21  * contributors may be used to endorse or promote products derived
22  * from this software without specific prior written permission.
23  *
24  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
25  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
26  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
27  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
28  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
29  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
30  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
32  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
33  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
34  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35  * POSSIBILITY OF SUCH DAMAGE.
36  *
37  * $Id$
38  *
39  */
40 
41 #pragma once
42 
43 #include <pcl/features/principal_curvatures.h>
44 
45 #include <pcl/common/point_tests.h> // for pcl::isFinite
46 
47 ///////////////////////////////////////////////////////////////////////////////////////////
48 template <typename PointInT, typename PointNT, typename PointOutT> void
50 {
51 #ifdef _OPENMP
52  if (nr_threads == 0)
53  threads_ = omp_get_num_procs();
54  else
55  threads_ = nr_threads;
56  PCL_DEBUG ("[pcl::PrincipalCurvaturesEstimation::setNumberOfThreads] Setting number of threads to %u.\n", threads_);
57 #else
58  threads_ = 1;
59  if (nr_threads != 1)
60  PCL_WARN ("[pcl::PrincipalCurvaturesEstimation::setNumberOfThreads] Parallelization is requested, but OpenMP is not available! Continuing without parallelization.\n");
61 #endif // _OPENMP
62 }
63 
64 //////////////////////////////////////////////////////////////////////////////////////////////
65 template <typename PointInT, typename PointNT, typename PointOutT> void
67  const pcl::PointCloud<PointNT> &normals, int p_idx, const pcl::Indices &indices,
68  float &pcx, float &pcy, float &pcz, float &pc1, float &pc2)
69 {
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 (); // projection matrix (into tangent plane)
73 
74  // Project normals into the tangent plane
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)
78  {
79  const auto normal = normals[indices[idx]].getNormalVector3fMap();
80  projected_normals[idx] = M * normal;
81  xyz_centroid += projected_normals[idx];
82  }
83 
84  // Estimate the XYZ centroid
85  xyz_centroid /= static_cast<float> (indices.size ());
86 
87  // Initialize to 0
88  EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix = Eigen::Matrix3f::Zero();
89 
90  // For each point in the cloud
91  for (std::size_t idx = 0; idx < indices.size (); ++idx)
92  {
93  const Eigen::Vector3f demean = projected_normals[idx] - xyz_centroid;
94 
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];
98 
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);
102 
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);
106 
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];
110  }
111 
112  // Extract the eigenvalues and eigenvectors
113  Eigen::Vector3f eigenvalues;
114  Eigen::Vector3f eigenvector;
115  pcl::eigen33 (covariance_matrix, eigenvalues);
116  pcl::computeCorrespondingEigenVector (covariance_matrix, eigenvalues [2], eigenvector);
117 
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;
124 }
125 
126 
127 //////////////////////////////////////////////////////////////////////////////////////////////
128 template <typename PointInT, typename PointNT, typename PointOutT> void
130 {
131  // Allocate enough space to hold the results
132  // \note This resize is irrelevant for a radiusSearch ().
133  pcl::Indices nn_indices (k_);
134  std::vector<float> nn_dists (k_);
135 
136  output.is_dense = true;
137  // Save a few cycles by not checking every point for NaN/Inf values if the cloud is set to dense
138  if (input_->is_dense)
139  {
140 #pragma omp parallel for \
141  default(none) \
142  shared(output) \
143  firstprivate(nn_indices, nn_dists) \
144  num_threads(threads_) \
145  schedule(dynamic, chunk_size_)
146  // Iterating over the entire index vector
147  for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t> (indices_->size ()); ++idx)
148  {
149  if (this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
150  {
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 ();
153  output.is_dense = false;
154  continue;
155  }
156 
157  // Estimate the principal curvatures at each patch
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);
161  }
162  }
163  else
164  {
165 #pragma omp parallel for \
166  default(none) \
167  shared(output) \
168  firstprivate(nn_indices, nn_dists) \
169  num_threads(threads_) \
170  schedule(dynamic, chunk_size_)
171  // Iterating over the entire index vector
172  for (std::ptrdiff_t idx = 0; idx < static_cast<std::ptrdiff_t> (indices_->size ()); ++idx)
173  {
174  if (!isFinite ((*input_)[(*indices_)[idx]]) ||
175  this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
176  {
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 ();
179  output.is_dense = false;
180  continue;
181  }
182 
183  // Estimate the principal curvatures at each patch
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);
187  }
188  }
189 }
190 
191 #define PCL_INSTANTIATE_PrincipalCurvaturesEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::PrincipalCurvaturesEstimation<T,NT,OutT>;
192 
bool is_dense
True if no points are invalid (e.g., have NaN or Inf values in any of their floating point fields).
Definition: point_cloud.h:403
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...
Definition: eigen.hpp:226
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...
Definition: eigen.hpp:295
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...
Definition: point_tests.h:55
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:133