Point Cloud Library (PCL)  1.14.0-dev
fpfh.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/fpfh.h>
44 
45 #include <pcl/common/point_tests.h> // for pcl::isFinite
46 #include <pcl/features/pfh_tools.h>
47 
48 #include <set> // for std::set
49 
50 //////////////////////////////////////////////////////////////////////////////////////////////
51 template <typename PointInT, typename PointNT, typename PointOutT> bool
53  const pcl::PointCloud<PointInT> &cloud, const pcl::PointCloud<PointNT> &normals,
54  int p_idx, int q_idx, float &f1, float &f2, float &f3, float &f4)
55 {
56  pcl::computePairFeatures (cloud[p_idx].getVector4fMap (), normals[p_idx].getNormalVector4fMap (),
57  cloud[q_idx].getVector4fMap (), normals[q_idx].getNormalVector4fMap (),
58  f1, f2, f3, f4);
59  return (true);
60 }
61 
62 //////////////////////////////////////////////////////////////////////////////////////////////
63 template <typename PointInT, typename PointNT, typename PointOutT> void
65  const pcl::PointCloud<PointInT> &cloud, const pcl::PointCloud<PointNT> &normals,
66  pcl::index_t p_idx, int row, const pcl::Indices &indices,
67  Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3)
68 {
69  Eigen::Vector4f pfh_tuple;
70  // Get the number of bins from the histograms size
71  // @TODO: use arrays
72  int nr_bins_f1 = static_cast<int> (hist_f1.cols ());
73  int nr_bins_f2 = static_cast<int> (hist_f2.cols ());
74  int nr_bins_f3 = static_cast<int> (hist_f3.cols ());
75 
76  // Factorization constant
77  float hist_incr = 100.0f / static_cast<float>(indices.size () - 1);
78 
79  // Iterate over all the points in the neighborhood
80  for (const auto &index : indices)
81  {
82  // Avoid unnecessary returns
83  if (p_idx == index)
84  continue;
85 
86  // Compute the pair P to NNi
87  if (!computePairFeatures (cloud, normals, p_idx, index, pfh_tuple[0], pfh_tuple[1], pfh_tuple[2], pfh_tuple[3]))
88  continue;
89 
90  // Normalize the f1, f2, f3 features and push them in the histogram
91  int h_index = static_cast<int> (std::floor (nr_bins_f1 * ((pfh_tuple[0] + M_PI) * d_pi_)));
92  if (h_index < 0) h_index = 0;
93  if (h_index >= nr_bins_f1) h_index = nr_bins_f1 - 1;
94  hist_f1 (row, h_index) += hist_incr;
95 
96  h_index = static_cast<int> (std::floor (nr_bins_f2 * ((pfh_tuple[1] + 1.0) * 0.5)));
97  if (h_index < 0) h_index = 0;
98  if (h_index >= nr_bins_f2) h_index = nr_bins_f2 - 1;
99  hist_f2 (row, h_index) += hist_incr;
100 
101  h_index = static_cast<int> (std::floor (nr_bins_f3 * ((pfh_tuple[2] + 1.0) * 0.5)));
102  if (h_index < 0) h_index = 0;
103  if (h_index >= nr_bins_f3) h_index = nr_bins_f3 - 1;
104  hist_f3 (row, h_index) += hist_incr;
105  }
106 }
107 
108 //////////////////////////////////////////////////////////////////////////////////////////////
109 template <typename PointInT, typename PointNT, typename PointOutT> void
111  const Eigen::MatrixXf &hist_f1, const Eigen::MatrixXf &hist_f2, const Eigen::MatrixXf &hist_f3,
112  const pcl::Indices &indices, const std::vector<float> &dists, Eigen::VectorXf &fpfh_histogram)
113 {
114  assert (indices.size () == dists.size ());
115  // @TODO: use arrays
116  double sum_f1 = 0.0, sum_f2 = 0.0, sum_f3 = 0.0;
117  float weight = 0.0, val_f1, val_f2, val_f3;
118 
119  // Get the number of bins from the histograms size
120  const auto nr_bins_f1 = hist_f1.cols ();
121  const auto nr_bins_f2 = hist_f2.cols ();
122  const auto nr_bins_f3 = hist_f3.cols ();
123  const auto nr_bins_f12 = nr_bins_f1 + nr_bins_f2;
124 
125  // Clear the histogram
126  fpfh_histogram.setZero (nr_bins_f1 + nr_bins_f2 + nr_bins_f3);
127 
128  // Use the entire patch
129  for (std::size_t idx = 0; idx < indices.size (); ++idx)
130  {
131  // Minus the query point itself
132  if (dists[idx] == 0)
133  continue;
134 
135  // Standard weighting function used
136  weight = 1.0f / dists[idx];
137 
138  // Weight the SPFH of the query point with the SPFH of its neighbors
139  for (Eigen::MatrixXf::Index f1_i = 0; f1_i < nr_bins_f1; ++f1_i)
140  {
141  val_f1 = hist_f1 (indices[idx], f1_i) * weight;
142  sum_f1 += val_f1;
143  fpfh_histogram[f1_i] += val_f1;
144  }
145 
146  for (Eigen::MatrixXf::Index f2_i = 0; f2_i < nr_bins_f2; ++f2_i)
147  {
148  val_f2 = hist_f2 (indices[idx], f2_i) * weight;
149  sum_f2 += val_f2;
150  fpfh_histogram[f2_i + nr_bins_f1] += val_f2;
151  }
152 
153  for (Eigen::MatrixXf::Index f3_i = 0; f3_i < nr_bins_f3; ++f3_i)
154  {
155  val_f3 = hist_f3 (indices[idx], f3_i) * weight;
156  sum_f3 += val_f3;
157  fpfh_histogram[f3_i + nr_bins_f12] += val_f3;
158  }
159  }
160 
161  if (sum_f1 != 0)
162  sum_f1 = 100.0 / sum_f1; // histogram values sum up to 100
163  if (sum_f2 != 0)
164  sum_f2 = 100.0 / sum_f2; // histogram values sum up to 100
165  if (sum_f3 != 0)
166  sum_f3 = 100.0 / sum_f3; // histogram values sum up to 100
167 
168  // Adjust final FPFH values
169  const auto denormalize_with = [](auto factor)
170  {
171  return [=](const auto& data) { return data * factor; };
172  };
173 
174  auto last = fpfh_histogram.data ();
175  last = std::transform(last, last + nr_bins_f1, last, denormalize_with (sum_f1));
176  last = std::transform(last, last + nr_bins_f2, last, denormalize_with (sum_f2));
177  std::transform(last, last + nr_bins_f3, last, denormalize_with (sum_f3));
178 }
179 
180 //////////////////////////////////////////////////////////////////////////////////////////////
181 template <typename PointInT, typename PointNT, typename PointOutT> void
183  Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3)
184 {
185  // Allocate enough space to hold the NN search results
186  // \note This resize is irrelevant for a radiusSearch ().
187  pcl::Indices nn_indices (k_);
188  std::vector<float> nn_dists (k_);
189 
190  std::set<int> spfh_indices;
191  spfh_hist_lookup.resize (surface_->size ());
192 
193  // Build a list of (unique) indices for which we will need to compute SPFH signatures
194  // (We need an SPFH signature for every point that is a neighbor of any point in input_[indices_])
195  if (surface_ != input_ ||
196  indices_->size () != surface_->size ())
197  {
198  for (const auto& p_idx: *indices_)
199  {
200  if (this->searchForNeighbors (p_idx, search_parameter_, nn_indices, nn_dists) == 0)
201  continue;
202 
203  spfh_indices.insert (nn_indices.begin (), nn_indices.end ());
204  }
205  }
206  else
207  {
208  // Special case: When a feature must be computed at every point, there is no need for a neighborhood search
209  for (std::size_t idx = 0; idx < indices_->size (); ++idx)
210  spfh_indices.insert (static_cast<int> (idx));
211  }
212 
213  // Initialize the arrays that will store the SPFH signatures
214  std::size_t data_size = spfh_indices.size ();
215  hist_f1.setZero (data_size, nr_bins_f1_);
216  hist_f2.setZero (data_size, nr_bins_f2_);
217  hist_f3.setZero (data_size, nr_bins_f3_);
218 
219  // Compute SPFH signatures for every point that needs them
220  std::size_t i = 0;
221  for (const auto& p_idx: spfh_indices)
222  {
223  // Find the neighborhood around p_idx
224  if (this->searchForNeighbors (*surface_, p_idx, search_parameter_, nn_indices, nn_dists) == 0)
225  continue;
226 
227  // Estimate the SPFH signature around p_idx
228  computePointSPFHSignature (*surface_, *normals_, p_idx, i, nn_indices, hist_f1, hist_f2, hist_f3);
229 
230  // Populate a lookup table for converting a point index to its corresponding row in the spfh_hist_* matrices
231  spfh_hist_lookup[p_idx] = i;
232  i++;
233  }
234 }
235 
236 //////////////////////////////////////////////////////////////////////////////////////////////
237 template <typename PointInT, typename PointNT, typename PointOutT> void
239 {
240  // Allocate enough space to hold the NN search results
241  // \note This resize is irrelevant for a radiusSearch ().
242  pcl::Indices nn_indices (k_);
243  std::vector<float> nn_dists (k_);
244 
245  std::vector<int> spfh_hist_lookup;
246  computeSPFHSignatures (spfh_hist_lookup, hist_f1_, hist_f2_, hist_f3_);
247 
248  output.is_dense = true;
249  // Save a few cycles by not checking every point for NaN/Inf values if the cloud is set to dense
250  if (input_->is_dense)
251  {
252  // Iterate over the entire index vector
253  for (std::size_t idx = 0; idx < indices_->size (); ++idx)
254  {
255  if (this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
256  {
257  for (Eigen::Index d = 0; d < fpfh_histogram_.size (); ++d)
258  output[idx].histogram[d] = std::numeric_limits<float>::quiet_NaN ();
259 
260  output.is_dense = false;
261  continue;
262  }
263 
264  // ... and remap the nn_indices values so that they represent row indices in the spfh_hist_* matrices
265  // instead of indices into surface_->points
266  for (auto &nn_index : nn_indices)
267  nn_index = spfh_hist_lookup[nn_index];
268 
269  // Compute the FPFH signature (i.e. compute a weighted combination of local SPFH signatures) ...
270  weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram_);
271 
272  // ...and copy it into the output cloud
273  std::copy_n(fpfh_histogram_.data (), fpfh_histogram_.size (), output[idx].histogram);
274  }
275  }
276  else
277  {
278  // Iterate over the entire index vector
279  for (std::size_t idx = 0; idx < indices_->size (); ++idx)
280  {
281  if (!isFinite ((*input_)[(*indices_)[idx]]) ||
282  this->searchForNeighbors ((*indices_)[idx], search_parameter_, nn_indices, nn_dists) == 0)
283  {
284  for (Eigen::Index d = 0; d < fpfh_histogram_.size (); ++d)
285  output[idx].histogram[d] = std::numeric_limits<float>::quiet_NaN ();
286 
287  output.is_dense = false;
288  continue;
289  }
290 
291  // ... and remap the nn_indices values so that they represent row indices in the spfh_hist_* matrices
292  // instead of indices into surface_->points
293  for (auto &nn_index : nn_indices)
294  nn_index = spfh_hist_lookup[nn_index];
295 
296  // Compute the FPFH signature (i.e. compute a weighted combination of local SPFH signatures) ...
297  weightPointSPFHSignature (hist_f1_, hist_f2_, hist_f3_, nn_indices, nn_dists, fpfh_histogram_);
298 
299  // ...and copy it into the output cloud
300  std::copy_n(fpfh_histogram_.data (), fpfh_histogram_.size (), output[idx].histogram);
301  }
302  }
303 }
304 
305 #define PCL_INSTANTIATE_FPFHEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::FPFHEstimation<T,NT,OutT>;
306 
void computeSPFHSignatures(std::vector< int > &spf_hist_lookup, Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3)
Estimate the set of all SPFH (Simple Point Feature Histograms) signatures for the input cloud.
Definition: fpfh.hpp:182
void computePointSPFHSignature(const pcl::PointCloud< PointInT > &cloud, const pcl::PointCloud< PointNT > &normals, pcl::index_t p_idx, int row, const pcl::Indices &indices, Eigen::MatrixXf &hist_f1, Eigen::MatrixXf &hist_f2, Eigen::MatrixXf &hist_f3)
Estimate the SPFH (Simple Point Feature Histograms) individual signatures of the three angular (f1,...
Definition: fpfh.hpp:64
void computeFeature(PointCloudOut &output) override
Estimate the Fast Point Feature Histograms (FPFH) descriptors at a set of points given by <setInputCl...
Definition: fpfh.hpp:238
bool computePairFeatures(const pcl::PointCloud< PointInT > &cloud, const pcl::PointCloud< PointNT > &normals, int p_idx, int q_idx, float &f1, float &f2, float &f3, float &f4)
Compute the 4-tuple representation containing the three angles and one distance between two points re...
Definition: fpfh.hpp:52
void weightPointSPFHSignature(const Eigen::MatrixXf &hist_f1, const Eigen::MatrixXf &hist_f2, const Eigen::MatrixXf &hist_f3, const pcl::Indices &indices, const std::vector< float > &dists, Eigen::VectorXf &fpfh_histogram)
Weight the SPFH (Simple Point Feature Histograms) individual histograms to create the final FPFH (Fas...
Definition: fpfh.hpp:110
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
PCL_EXPORTS bool computePairFeatures(const Eigen::Vector4f &p1, const Eigen::Vector4f &n1, const Eigen::Vector4f &p2, const Eigen::Vector4f &n2, float &f1, float &f2, float &f3, float &f4)
Compute the 4-tuple representation containing the three angles and one distance between two points re...
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
detail::int_type_t< detail::index_type_size, detail::index_type_signed > index_t
Type used for an index in PCL.
Definition: types.h:112
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:133
#define M_PI
Definition: pcl_macros.h:201