Point Cloud Library (PCL)  1.14.0-dev
sampling_surface_normal.hpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2009-2011, Willow Garage, Inc.
6  *
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the copyright holder(s) nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  */
37 
38 #ifndef PCL_FILTERS_IMPL_SAMPLING_SURFACE_NORMAL_H_
39 #define PCL_FILTERS_IMPL_SAMPLING_SURFACE_NORMAL_H_
40 
41 #include <iostream>
42 #include <vector>
43 #include <pcl/common/eigen.h>
44 #include <pcl/common/point_tests.h> // for pcl::isFinite
45 #include <pcl/filters/sampling_surface_normal.h>
46 
47 ///////////////////////////////////////////////////////////////////////////////
48 template<typename PointT> void
50 {
51  Indices indices;
52  std::size_t npts = input_->size ();
53  for (std::size_t i = 0; i < npts; i++)
54  indices.push_back (i);
55 
56  Vector max_vec (3, 1);
57  Vector min_vec (3, 1);
58  findXYZMaxMin (*input_, max_vec, min_vec);
59  PointCloud data = *input_;
60  partition (data, 0, npts, min_vec, max_vec, indices, output);
61  output.height = 1;
62  output.width = output.size ();
63 }
64 
65 ///////////////////////////////////////////////////////////////////////////////
66 template<typename PointT> void
67 pcl::SamplingSurfaceNormal<PointT>::findXYZMaxMin (const PointCloud& cloud, Vector& max_vec, Vector& min_vec)
68 {
69  // 4f to ease vectorization
70  Eigen::Array4f min_array =
71  Eigen::Array4f::Constant(std::numeric_limits<float>::max());
72  Eigen::Array4f max_array =
73  Eigen::Array4f::Constant(std::numeric_limits<float>::lowest());
74 
75  for (const auto& point : cloud) {
76  min_array = min_array.min(point.getArray4fMap());
77  max_array = max_array.max(point.getArray4fMap());
78  }
79 
80  max_vec = max_array.head<3>();
81  min_vec = min_array.head<3>();
82 }
83 
84 ///////////////////////////////////////////////////////////////////////////////
85 template<typename PointT> void
87  const PointCloud& cloud, const int first, const int last,
88  const Vector min_values, const Vector max_values,
89  Indices& indices, PointCloud& output)
90 {
91  const int count (last - first);
92  if (count <= static_cast<int> (sample_))
93  {
94  samplePartition (cloud, first, last, indices, output);
95  return;
96  }
97  int cutDim = 0;
98  (max_values - min_values).maxCoeff (&cutDim);
99 
100  const int rightCount (count / 2);
101  const int leftCount (count - rightCount);
102  assert (last - rightCount == first + leftCount);
103 
104  // sort, hack std::nth_element
105  std::nth_element (indices.begin () + first, indices.begin () + first + leftCount,
106  indices.begin () + last, CompareDim (cutDim, cloud));
107 
108  const int cutIndex (indices[first+leftCount]);
109  const float cutVal = findCutVal (cloud, cutDim, cutIndex);
110 
111  // update bounds for left
112  Vector leftMaxValues (max_values);
113  leftMaxValues[cutDim] = cutVal;
114  // update bounds for right
115  Vector rightMinValues (min_values);
116  rightMinValues[cutDim] = cutVal;
117 
118  // recurse
119  partition (cloud, first, first + leftCount, min_values, leftMaxValues, indices, output);
120  partition (cloud, first + leftCount, last, rightMinValues, max_values, indices, output);
121 }
122 
123 ///////////////////////////////////////////////////////////////////////////////
124 template<typename PointT> void
126  const PointCloud& data, const int first, const int last,
127  Indices& indices, PointCloud& output)
128 {
130 
131  for (int i = first; i < last; i++)
132  {
133  PointT pt;
134  pt.x = data[indices[i]].x;
135  pt.y = data[indices[i]].y;
136  pt.z = data[indices[i]].z;
137  cloud.push_back (pt);
138  }
139  cloud.height = 1;
140  cloud.width = cloud.size ();
141 
142  Eigen::Vector4f normal;
143  float curvature = 0;
144  //pcl::computePointNormal<PointT> (cloud, normal, curvature);
145 
146  computeNormal (cloud, normal, curvature);
147 
148  for (const auto& point: cloud)
149  {
150  // TODO: change to Boost random number generators!
151  const float r = static_cast<float>(std::rand ()) / static_cast<float>(RAND_MAX);
152 
153  if (r < ratio_)
154  {
155  PointT pt = point;
156  pt.normal[0] = normal (0);
157  pt.normal[1] = normal (1);
158  pt.normal[2] = normal (2);
159  pt.curvature = curvature;
160 
161  output.push_back (pt);
162  }
163  }
164 }
165 
166 ///////////////////////////////////////////////////////////////////////////////
167 template<typename PointT> void
168 pcl::SamplingSurfaceNormal<PointT>::computeNormal (const PointCloud& cloud, Eigen::Vector4f &normal, float& curvature)
169 {
170  EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
171  Eigen::Vector4f xyz_centroid;
172  float nx = 0.0;
173  float ny = 0.0;
174  float nz = 0.0;
175 
176  if (computeMeanAndCovarianceMatrix (cloud, covariance_matrix, xyz_centroid) == 0)
177  {
178  nx = ny = nz = curvature = std::numeric_limits<float>::quiet_NaN ();
179  return;
180  }
181 
182  // Get the plane normal and surface curvature
183  solvePlaneParameters (covariance_matrix, nx, ny, nz, curvature);
184  normal (0) = nx;
185  normal (1) = ny;
186  normal (2) = nz;
187 
188  normal (3) = 0;
189  // Hessian form (D = nc . p_plane (centroid here) + p)
190  normal (3) = -1 * normal.dot (xyz_centroid);
191 }
192 
193 //////////////////////////////////////////////////////////////////////////////////////////////
194 template <typename PointT> inline unsigned int
196  Eigen::Matrix3f &covariance_matrix,
197  Eigen::Vector4f &centroid)
198 {
199  // create the buffer on the stack which is much faster than using cloud[indices[i]] and centroid as a buffer
200  Eigen::Matrix<float, 1, 9, Eigen::RowMajor> accu = Eigen::Matrix<float, 1, 9, Eigen::RowMajor>::Zero ();
201  std::size_t point_count = 0;
202  for (const auto& point: cloud)
203  {
204  if (!isXYZFinite (point))
205  {
206  continue;
207  }
208 
209  ++point_count;
210  accu [0] += point.x * point.x;
211  accu [1] += point.x * point.y;
212  accu [2] += point.x * point.z;
213  accu [3] += point.y * point.y; // 4
214  accu [4] += point.y * point.z; // 5
215  accu [5] += point.z * point.z; // 8
216  accu [6] += point.x;
217  accu [7] += point.y;
218  accu [8] += point.z;
219  }
220 
221  accu /= static_cast<float> (point_count);
222  centroid[0] = accu[6]; centroid[1] = accu[7]; centroid[2] = accu[8];
223  centroid[3] = 0;
224  covariance_matrix.coeffRef (0) = accu [0] - accu [6] * accu [6];
225  covariance_matrix.coeffRef (1) = accu [1] - accu [6] * accu [7];
226  covariance_matrix.coeffRef (2) = accu [2] - accu [6] * accu [8];
227  covariance_matrix.coeffRef (4) = accu [3] - accu [7] * accu [7];
228  covariance_matrix.coeffRef (5) = accu [4] - accu [7] * accu [8];
229  covariance_matrix.coeffRef (8) = accu [5] - accu [8] * accu [8];
230  covariance_matrix.coeffRef (3) = covariance_matrix.coeff (1);
231  covariance_matrix.coeffRef (6) = covariance_matrix.coeff (2);
232  covariance_matrix.coeffRef (7) = covariance_matrix.coeff (5);
233 
234  return (static_cast<unsigned int> (point_count));
235 }
236 
237 //////////////////////////////////////////////////////////////////////////////////////////////
238 template <typename PointT> void
239 pcl::SamplingSurfaceNormal<PointT>::solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix,
240  float &nx, float &ny, float &nz, float &curvature)
241 {
242  // Extract the smallest eigenvalue and its eigenvector
243  EIGEN_ALIGN16 Eigen::Vector3f::Scalar eigen_value;
244  EIGEN_ALIGN16 Eigen::Vector3f eigen_vector;
245  pcl::eigen33 (covariance_matrix, eigen_value, eigen_vector);
246 
247  nx = eigen_vector [0];
248  ny = eigen_vector [1];
249  nz = eigen_vector [2];
250 
251  // Compute the curvature surface change
252  float eig_sum = covariance_matrix.coeff (0) + covariance_matrix.coeff (4) + covariance_matrix.coeff (8);
253  if (eig_sum != 0)
254  curvature = std::abs (eigen_value / eig_sum);
255  else
256  curvature = 0;
257 }
258 
259 ///////////////////////////////////////////////////////////////////////////////
260 template <typename PointT> float
262  const PointCloud& cloud, const int cut_dim, const int cut_index)
263 {
264  if (cut_dim == 0)
265  return (cloud[cut_index].x);
266  if (cut_dim == 1)
267  return (cloud[cut_index].y);
268  if (cut_dim == 2)
269  return (cloud[cut_index].z);
270 
271  return (0.0f);
272 }
273 
274 
275 #define PCL_INSTANTIATE_SamplingSurfaceNormal(T) template class PCL_EXPORTS pcl::SamplingSurfaceNormal<T>;
276 
277 #endif // PCL_FILTERS_IMPL_NORMAL_SPACE_SAMPLE_H_
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: point_cloud.h:173
void push_back(const PointT &pt)
Insert a new point in the cloud, at the end of the container.
Definition: point_cloud.h:663
std::uint32_t width
The point cloud width (if organized as an image-structure).
Definition: point_cloud.h:398
std::uint32_t height
The point cloud height (if organized as an image-structure).
Definition: point_cloud.h:400
std::size_t size() const
Definition: point_cloud.h:443
SamplingSurfaceNormal divides the input space into grids until each grid contains a maximum of N poin...
void applyFilter(PointCloud &output) override
Sample of point indices into a separate PointCloud.
unsigned int computeMeanAndCovarianceMatrix(const pcl::PointCloud< PointT > &cloud, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix, Eigen::Matrix< Scalar, 4, 1 > &centroid)
Compute the normalized 3x3 covariance matrix and the centroid of a given set of points in a single lo...
Definition: centroid.hpp:509
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
void solvePlaneParameters(const Eigen::Matrix3f &covariance_matrix, const Eigen::Vector4f &point, Eigen::Vector4f &plane_parameters, float &curvature)
Solve the eigenvalues and eigenvectors of a given 3x3 covariance matrix, and estimate the least-squar...
Definition: feature.hpp:52
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:133
A point structure representing Euclidean xyz coordinates, and the RGB color.