Point Cloud Library (PCL)  1.14.1-dev
our_cvfh.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: cvfh.hpp 5311 2012-03-26 22:02:04Z aaldoma $
38  *
39  */
40 
41 #ifndef PCL_FEATURES_IMPL_OURCVFH_H_
42 #define PCL_FEATURES_IMPL_OURCVFH_H_
43 
44 #include <pcl/features/our_cvfh.h>
45 #include <pcl/features/vfh.h>
46 #include <pcl/features/normal_3d.h>
47 #include <pcl/common/io.h> // for copyPointCloud
48 #include <pcl/common/common.h> // for getMaxDistance
49 #include <pcl/common/transforms.h>
50 
51 //////////////////////////////////////////////////////////////////////////////////////////////
52 template<typename PointInT, typename PointNT, typename PointOutT> void
54 {
56  {
57  output.width = output.height = 0;
58  output.clear ();
59  return;
60  }
61  // Resize the output dataset
62  // Important! We should only allocate precisely how many elements we will need, otherwise
63  // we risk at pre-allocating too much memory which could lead to bad_alloc
64  // (see http://dev.pointclouds.org/issues/657)
65  output.width = output.height = 1;
66  output.resize (1);
67 
68  // Perform the actual feature computation
69  computeFeature (output);
70 
72 }
73 
74 //////////////////////////////////////////////////////////////////////////////////////////////
75 template<typename PointInT, typename PointNT, typename PointOutT> void
77  const pcl::PointCloud<pcl::PointNormal> &normals,
78  float tolerance,
80  std::vector<pcl::PointIndices> &clusters, double eps_angle,
81  unsigned int min_pts_per_cluster,
82  unsigned int max_pts_per_cluster)
83 {
84  if (tree->getInputCloud ()->size () != cloud.size ())
85  {
86  PCL_ERROR("[pcl::extractEuclideanClusters] Tree built for a different point cloud "
87  "dataset (%zu) than the input cloud (%zu)!\n",
88  static_cast<std::size_t>(tree->getInputCloud()->size()),
89  static_cast<std::size_t>(cloud.size()));
90  return;
91  }
92  if (cloud.size () != normals.size ())
93  {
94  PCL_ERROR("[pcl::extractEuclideanClusters] Number of points in the input point "
95  "cloud (%zu) different than normals (%zu)!\n",
96  static_cast<std::size_t>(cloud.size()),
97  static_cast<std::size_t>(normals.size()));
98  return;
99  }
100  // If tree gives sorted results, we can skip the first one because it is the query point itself
101  const std::size_t nn_start_idx = tree->getSortedResults () ? 1 : 0;
102 
103  // Create a bool vector of processed point indices, and initialize it to false
104  std::vector<bool> processed (cloud.size (), false);
105 
106  pcl::Indices nn_indices;
107  std::vector<float> nn_distances;
108  // Process all points in the indices vector
109  for (std::size_t i = 0; i < cloud.size (); ++i)
110  {
111  if (processed[i])
112  continue;
113 
114  std::vector<std::size_t> seed_queue;
115  std::size_t sq_idx = 0;
116  seed_queue.push_back (i);
117 
118  processed[i] = true;
119 
120  while (sq_idx < seed_queue.size ())
121  {
122  // Search for sq_idx
123  if (!tree->radiusSearch (seed_queue[sq_idx], tolerance, nn_indices, nn_distances))
124  {
125  sq_idx++;
126  continue;
127  }
128 
129  for (std::size_t j = nn_start_idx; j < nn_indices.size (); ++j)
130  {
131  if (processed[nn_indices[j]]) // Has this point been processed before ?
132  continue;
133 
134  //processed[nn_indices[j]] = true;
135  // [-1;1]
136 
137  double dot_p = normals[seed_queue[sq_idx]].normal[0] * normals[nn_indices[j]].normal[0]
138  + normals[seed_queue[sq_idx]].normal[1] * normals[nn_indices[j]].normal[1] + normals[seed_queue[sq_idx]].normal[2]
139  * normals[nn_indices[j]].normal[2];
140 
141  if (std::abs (std::acos (dot_p)) < eps_angle)
142  {
143  processed[nn_indices[j]] = true;
144  seed_queue.push_back (nn_indices[j]);
145  }
146  }
147 
148  sq_idx++;
149  }
150 
151  // If this queue is satisfactory, add to the clusters
152  if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster)
153  {
155  r.indices.resize (seed_queue.size ());
156  for (std::size_t j = 0; j < seed_queue.size (); ++j)
157  r.indices[j] = seed_queue[j];
158 
159  std::sort (r.indices.begin (), r.indices.end ());
160  r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ());
161 
162  r.header = cloud.header;
163  clusters.push_back (r); // We could avoid a copy by working directly in the vector
164  }
165  }
166 }
167 
168 //////////////////////////////////////////////////////////////////////////////////////////////
169 template<typename PointInT, typename PointNT, typename PointOutT> void
171  pcl::Indices &indices_to_use,
172  pcl::Indices &indices_out, pcl::Indices &indices_in,
173  float threshold)
174 {
175  indices_out.resize (cloud.size ());
176  indices_in.resize (cloud.size ());
177 
178  std::size_t in, out;
179  in = out = 0;
180 
181  for (const auto &index : indices_to_use)
182  {
183  if (cloud[index].curvature > threshold)
184  {
185  indices_out[out] = index;
186  out++;
187  }
188  else
189  {
190  indices_in[in] = index;
191  in++;
192  }
193  }
194 
195  indices_out.resize (out);
196  indices_in.resize (in);
197 }
198 
199 template<typename PointInT, typename PointNT, typename PointOutT> bool
200 pcl::OURCVFHEstimation<PointInT, PointNT, PointOutT>::sgurf (Eigen::Vector3f & centroid, Eigen::Vector3f & normal_centroid,
201  PointInTPtr & processed, std::vector<Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > & transformations,
202  PointInTPtr & grid, pcl::PointIndices & indices)
203 {
204 
205  Eigen::Vector3f plane_normal;
206  plane_normal[0] = -centroid[0];
207  plane_normal[1] = -centroid[1];
208  plane_normal[2] = -centroid[2];
209  Eigen::Vector3f z_vector = Eigen::Vector3f::UnitZ ();
210  plane_normal.normalize ();
211  Eigen::Vector3f axis = plane_normal.cross (z_vector);
212  double rotation = -asin (axis.norm ());
213  axis.normalize ();
214 
215  Eigen::Affine3f transformPC (Eigen::AngleAxisf (static_cast<float> (rotation), axis));
216 
217  grid->resize (processed->size ());
218  for (std::size_t k = 0; k < processed->size (); k++)
219  (*grid)[k].getVector4fMap () = (*processed)[k].getVector4fMap ();
220 
221  pcl::transformPointCloud (*grid, *grid, transformPC);
222 
223  Eigen::Vector4f centroid4f (centroid[0], centroid[1], centroid[2], 0);
224  Eigen::Vector4f normal_centroid4f (normal_centroid[0], normal_centroid[1], normal_centroid[2], 0);
225 
226  centroid4f = transformPC * centroid4f;
227  normal_centroid4f = transformPC * normal_centroid4f;
228 
229  Eigen::Vector3f centroid3f (centroid4f[0], centroid4f[1], centroid4f[2]);
230 
231  Eigen::Vector4f farthest_away;
232  pcl::getMaxDistance (*grid, indices.indices, centroid4f, farthest_away);
233  farthest_away[3] = 0;
234 
235  float max_dist = (farthest_away - centroid4f).norm ();
236 
237  pcl::demeanPointCloud (*grid, centroid4f, *grid);
238 
239  Eigen::Matrix4f center_mat;
240  center_mat.setIdentity (4, 4);
241  center_mat (0, 3) = -centroid4f[0];
242  center_mat (1, 3) = -centroid4f[1];
243  center_mat (2, 3) = -centroid4f[2];
244 
245  Eigen::Matrix3f scatter;
246  scatter.setZero ();
247  float sum_w = 0.f;
248 
249  for (const auto &index : indices.indices)
250  {
251  Eigen::Vector3f pvector = (*grid)[index].getVector3fMap ();
252  float d_k = (pvector).norm ();
253  float w = (max_dist - d_k);
254  Eigen::Vector3f diff = (pvector);
255  Eigen::Matrix3f mat = diff * diff.transpose ();
256  scatter += mat * w;
257  sum_w += w;
258  }
259 
260  scatter /= sum_w;
261 
262  Eigen::JacobiSVD <Eigen::MatrixXf> svd (scatter, Eigen::ComputeFullV);
263  Eigen::Vector3f evx = svd.matrixV ().col (0);
264  Eigen::Vector3f evy = svd.matrixV ().col (1);
265  Eigen::Vector3f evz = svd.matrixV ().col (2);
266  Eigen::Vector3f evxminus = evx * -1;
267  Eigen::Vector3f evyminus = evy * -1;
268  Eigen::Vector3f evzminus = evz * -1;
269 
270  float s_xplus, s_xminus, s_yplus, s_yminus;
271  s_xplus = s_xminus = s_yplus = s_yminus = 0.f;
272 
273  //disambiguate rf using all points
274  for (const auto& point: grid->points)
275  {
276  Eigen::Vector3f pvector = point.getVector3fMap ();
277  float dist_x, dist_y;
278  dist_x = std::abs (evx.dot (pvector));
279  dist_y = std::abs (evy.dot (pvector));
280 
281  if ((pvector).dot (evx) >= 0)
282  s_xplus += dist_x;
283  else
284  s_xminus += dist_x;
285 
286  if ((pvector).dot (evy) >= 0)
287  s_yplus += dist_y;
288  else
289  s_yminus += dist_y;
290 
291  }
292 
293  if (s_xplus < s_xminus)
294  evx = evxminus;
295 
296  if (s_yplus < s_yminus)
297  evy = evyminus;
298 
299  //select the axis that could be disambiguated more easily
300  float fx, fy;
301  float max_x = static_cast<float> (std::max (s_xplus, s_xminus));
302  float min_x = static_cast<float> (std::min (s_xplus, s_xminus));
303  float max_y = static_cast<float> (std::max (s_yplus, s_yminus));
304  float min_y = static_cast<float> (std::min (s_yplus, s_yminus));
305 
306  fx = (min_x / max_x);
307  fy = (min_y / max_y);
308 
309  Eigen::Vector3f normal3f = Eigen::Vector3f (normal_centroid4f[0], normal_centroid4f[1], normal_centroid4f[2]);
310  if (normal3f.dot (evz) < 0)
311  evz = evzminus;
312 
313  //if fx/y close to 1, it was hard to disambiguate
314  //what if both are equally easy or difficult to disambiguate, namely fy == fx or very close
315 
316  float max_axis = std::max (fx, fy);
317  float min_axis = std::min (fx, fy);
318 
319  if ((min_axis / max_axis) > axis_ratio_)
320  {
321  PCL_WARN ("Both axes are equally easy/difficult to disambiguate\n");
322 
323  Eigen::Vector3f evy_copy = evy;
324  Eigen::Vector3f evxminus = evx * -1;
325  Eigen::Vector3f evyminus = evy * -1;
326 
327  if (min_axis > min_axis_value_)
328  {
329  //combination of all possibilities
330  evy = evx.cross (evz);
331  Eigen::Matrix4f trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat);
332  transformations.push_back (trans);
333 
334  evx = evxminus;
335  evy = evx.cross (evz);
336  trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat);
337  transformations.push_back (trans);
338 
339  evx = evy_copy;
340  evy = evx.cross (evz);
341  trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat);
342  transformations.push_back (trans);
343 
344  evx = evyminus;
345  evy = evx.cross (evz);
346  trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat);
347  transformations.push_back (trans);
348 
349  }
350  else
351  {
352  //1-st case (evx selected)
353  evy = evx.cross (evz);
354  Eigen::Matrix4f trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat);
355  transformations.push_back (trans);
356 
357  //2-nd case (evy selected)
358  evx = evy_copy;
359  evy = evx.cross (evz);
360  trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat);
361  transformations.push_back (trans);
362  }
363  }
364  else
365  {
366  if (fy < fx)
367  {
368  evx = evy;
369  fx = fy;
370  }
371 
372  evy = evx.cross (evz);
373  Eigen::Matrix4f trans = createTransFromAxes (evx, evy, evz, transformPC, center_mat);
374  transformations.push_back (trans);
375 
376  }
377 
378  return true;
379 }
380 
381 //////////////////////////////////////////////////////////////////////////////////////////////
382 template<typename PointInT, typename PointNT, typename PointOutT> void
384  std::vector<pcl::PointIndices> & cluster_indices)
385 {
386  PointCloudOut ourcvfh_output;
387 
388  cluster_axes_.clear ();
389  cluster_axes_.resize (centroids_dominant_orientations_.size ());
390 
391  for (std::size_t i = 0; i < centroids_dominant_orientations_.size (); i++)
392  {
393 
394  std::vector < Eigen::Matrix4f, Eigen::aligned_allocator<Eigen::Matrix4f> > transformations;
396  sgurf (centroids_dominant_orientations_[i], dominant_normals_[i], processed, transformations, grid, cluster_indices[i]);
397 
398  // Make a note of how many transformations correspond to each cluster
399  cluster_axes_[i] = transformations.size ();
400 
401  for (const auto &transformation : transformations)
402  {
403 
404  pcl::transformPointCloud (*processed, *grid, transformation);
405  transforms_.push_back (transformation);
406  valid_transforms_.push_back (true);
407 
408  std::vector < Eigen::VectorXf > quadrants (8);
409  int size_hists = 13;
410  int num_hists = 8;
411  for (int k = 0; k < num_hists; k++)
412  quadrants[k].setZero (size_hists);
413 
414  Eigen::Vector4f centroid_p;
415  centroid_p.setZero ();
416  Eigen::Vector4f max_pt;
417  pcl::getMaxDistance (*grid, centroid_p, max_pt);
418  max_pt[3] = 0;
419  double distance_normalization_factor = (centroid_p - max_pt).norm ();
420 
421  float hist_incr;
422  if (normalize_bins_)
423  hist_incr = 100.0f / static_cast<float> (grid->size () - 1);
424  else
425  hist_incr = 1.0f;
426 
427  float * weights = new float[num_hists];
428  float sigma = 0.01f; //1cm
429  float sigma_sq = sigma * sigma;
430 
431  for (const auto& point: grid->points)
432  {
433  Eigen::Vector4f p = point.getVector4fMap ();
434  p[3] = 0.f;
435  float d = p.norm ();
436 
437  //compute weight for all octants
438  float wx = 1.f - std::exp (-((p[0] * p[0]) / (2.f * sigma_sq))); //how is the weight distributed among two semi-cubes
439  float wy = 1.f - std::exp (-((p[1] * p[1]) / (2.f * sigma_sq)));
440  float wz = 1.f - std::exp (-((p[2] * p[2]) / (2.f * sigma_sq)));
441 
442  //distribute the weights using the x-coordinate
443  if (p[0] >= 0)
444  {
445  for (std::size_t ii = 0; ii <= 3; ii++)
446  weights[ii] = 0.5f - wx * 0.5f;
447 
448  for (std::size_t ii = 4; ii <= 7; ii++)
449  weights[ii] = 0.5f + wx * 0.5f;
450  }
451  else
452  {
453  for (std::size_t ii = 0; ii <= 3; ii++)
454  weights[ii] = 0.5f + wx * 0.5f;
455 
456  for (std::size_t ii = 4; ii <= 7; ii++)
457  weights[ii] = 0.5f - wx * 0.5f;
458  }
459 
460  //distribute the weights using the y-coordinate
461  if (p[1] >= 0)
462  {
463  for (std::size_t ii = 0; ii <= 1; ii++)
464  weights[ii] *= 0.5f - wy * 0.5f;
465  for (std::size_t ii = 4; ii <= 5; ii++)
466  weights[ii] *= 0.5f - wy * 0.5f;
467 
468  for (std::size_t ii = 2; ii <= 3; ii++)
469  weights[ii] *= 0.5f + wy * 0.5f;
470 
471  for (std::size_t ii = 6; ii <= 7; ii++)
472  weights[ii] *= 0.5f + wy * 0.5f;
473  }
474  else
475  {
476  for (std::size_t ii = 0; ii <= 1; ii++)
477  weights[ii] *= 0.5f + wy * 0.5f;
478  for (std::size_t ii = 4; ii <= 5; ii++)
479  weights[ii] *= 0.5f + wy * 0.5f;
480 
481  for (std::size_t ii = 2; ii <= 3; ii++)
482  weights[ii] *= 0.5f - wy * 0.5f;
483 
484  for (std::size_t ii = 6; ii <= 7; ii++)
485  weights[ii] *= 0.5f - wy * 0.5f;
486  }
487 
488  //distribute the weights using the z-coordinate
489  if (p[2] >= 0)
490  {
491  for (std::size_t ii = 0; ii <= 7; ii += 2)
492  weights[ii] *= 0.5f - wz * 0.5f;
493 
494  for (std::size_t ii = 1; ii <= 7; ii += 2)
495  weights[ii] *= 0.5f + wz * 0.5f;
496 
497  }
498  else
499  {
500  for (std::size_t ii = 0; ii <= 7; ii += 2)
501  weights[ii] *= 0.5f + wz * 0.5f;
502 
503  for (std::size_t ii = 1; ii <= 7; ii += 2)
504  weights[ii] *= 0.5f - wz * 0.5f;
505  }
506 
507  int h_index = (d <= 0) ? 0 : std::ceil (size_hists * (d / distance_normalization_factor)) - 1;
508  /* from http://www.pcl-users.org/OUR-CVFH-problem-td4028436.html
509  h_index will be 13 when d is computed on the farthest away point.
510 
511  adding the following after computing h_index fixes the problem:
512  */
513  if(h_index > 12)
514  h_index = 12;
515  for (int j = 0; j < num_hists; j++)
516  quadrants[j][h_index] += hist_incr * weights[j];
517 
518  }
519 
520  //copy to the cvfh signature
521  PointCloudOut vfh_signature;
522  vfh_signature.resize (1);
523  vfh_signature.width = vfh_signature.height = 1;
524  for (int d = 0; d < 308; ++d)
525  vfh_signature[0].histogram[d] = output[i].histogram[d];
526 
527  int pos = 45 * 3;
528  for (int k = 0; k < num_hists; k++)
529  {
530  for (int ii = 0; ii < size_hists; ii++, pos++)
531  {
532  vfh_signature[0].histogram[pos] = quadrants[k][ii];
533  }
534  }
535 
536  ourcvfh_output.push_back (vfh_signature[0]);
537  ourcvfh_output.width = ourcvfh_output.size ();
538  delete[] weights;
539  }
540  }
541 
542  if (!ourcvfh_output.empty ())
543  {
544  ourcvfh_output.height = 1;
545  }
546  output = ourcvfh_output;
547 }
548 
549 //////////////////////////////////////////////////////////////////////////////////////////////
550 template<typename PointInT, typename PointNT, typename PointOutT> void
552 {
553  if (refine_clusters_ <= 0.f)
554  refine_clusters_ = 1.f;
555 
556  // Check if input was set
557  if (!normals_)
558  {
559  PCL_ERROR ("[pcl::%s::computeFeature] No input dataset containing normals was given!\n", getClassName ().c_str ());
560  output.width = output.height = 0;
561  output.clear ();
562  return;
563  }
564  if (normals_->size () != surface_->size ())
565  {
566  PCL_ERROR ("[pcl::%s::computeFeature] The number of points in the input dataset differs from the number of points in the dataset containing the normals!\n", getClassName ().c_str ());
567  output.width = output.height = 0;
568  output.clear ();
569  return;
570  }
571 
572  centroids_dominant_orientations_.clear ();
573  clusters_.clear ();
574  transforms_.clear ();
575  dominant_normals_.clear ();
576 
577  // ---[ Step 0: remove normals with high curvature
578  pcl::Indices indices_out;
579  pcl::Indices indices_in;
580  filterNormalsWithHighCurvature (*normals_, *indices_, indices_out, indices_in, curv_threshold_);
581 
583  normals_filtered_cloud->width = indices_in.size ();
584  normals_filtered_cloud->height = 1;
585  normals_filtered_cloud->points.resize (normals_filtered_cloud->width);
586 
587  pcl::Indices indices_from_nfc_to_indices;
588  indices_from_nfc_to_indices.resize (indices_in.size ());
589 
590  for (std::size_t i = 0; i < indices_in.size (); ++i)
591  {
592  (*normals_filtered_cloud)[i].x = (*surface_)[indices_in[i]].x;
593  (*normals_filtered_cloud)[i].y = (*surface_)[indices_in[i]].y;
594  (*normals_filtered_cloud)[i].z = (*surface_)[indices_in[i]].z;
595  //(*normals_filtered_cloud)[i].getNormalVector4fMap() = (*normals_)[indices_in[i]].getNormalVector4fMap();
596  indices_from_nfc_to_indices[i] = indices_in[i];
597  }
598 
599  std::vector<pcl::PointIndices> clusters;
600 
601  if (normals_filtered_cloud->size () >= min_points_)
602  {
603  //recompute normals and use them for clustering
604  {
605  KdTreePtr normals_tree_filtered (new pcl::search::KdTree<pcl::PointNormal> (false));
606  normals_tree_filtered->setInputCloud (normals_filtered_cloud);
608  n3d.setRadiusSearch (radius_normals_);
609  n3d.setSearchMethod (normals_tree_filtered);
610  n3d.setInputCloud (normals_filtered_cloud);
611  n3d.compute (*normals_filtered_cloud);
612  }
613 
614  KdTreePtr normals_tree (new pcl::search::KdTree<pcl::PointNormal> (false));
615  normals_tree->setInputCloud (normals_filtered_cloud);
616 
617  extractEuclideanClustersSmooth (*normals_filtered_cloud, *normals_filtered_cloud, cluster_tolerance_, normals_tree, clusters,
618  eps_angle_threshold_, static_cast<unsigned int> (min_points_));
619 
620  std::vector<pcl::PointIndices> clusters_filtered;
621  int cluster_filtered_idx = 0;
622  for (const auto &cluster : clusters)
623  {
624 
626  pcl::PointIndices pi_cvfh;
627  pcl::PointIndices pi_filtered;
628 
629  clusters_.push_back (pi);
630  clusters_filtered.push_back (pi_filtered);
631 
632  Eigen::Vector4f avg_normal = Eigen::Vector4f::Zero ();
633  Eigen::Vector4f avg_centroid = Eigen::Vector4f::Zero ();
634 
635  for (const auto &index : cluster.indices)
636  {
637  avg_normal += (*normals_filtered_cloud)[index].getNormalVector4fMap ();
638  avg_centroid += (*normals_filtered_cloud)[index].getVector4fMap ();
639  }
640 
641  avg_normal /= static_cast<float> (cluster.indices.size ());
642  avg_centroid /= static_cast<float> (cluster.indices.size ());
643  avg_normal.normalize ();
644 
645  Eigen::Vector3f avg_norm (avg_normal[0], avg_normal[1], avg_normal[2]);
646  Eigen::Vector3f avg_dominant_centroid (avg_centroid[0], avg_centroid[1], avg_centroid[2]);
647 
648  for (const auto &index : cluster.indices)
649  {
650  //decide if normal should be added
651  double dot_p = avg_normal.dot ((*normals_filtered_cloud)[index].getNormalVector4fMap ());
652  if (std::abs (std::acos (dot_p)) < (eps_angle_threshold_ * refine_clusters_))
653  {
654  clusters_[cluster_filtered_idx].indices.push_back (indices_from_nfc_to_indices[index]);
655  clusters_filtered[cluster_filtered_idx].indices.push_back (index);
656  }
657  }
658 
659  //remove last cluster if no points found...
660  if (clusters_[cluster_filtered_idx].indices.empty ())
661  {
662  clusters_.pop_back ();
663  clusters_filtered.pop_back ();
664  }
665  else
666  cluster_filtered_idx++;
667  }
668 
669  clusters = clusters_filtered;
670 
671  }
672 
674  vfh.setInputCloud (surface_);
675  vfh.setInputNormals (normals_);
676  vfh.setIndices (indices_);
677  vfh.setSearchMethod (this->tree_);
678  vfh.setUseGivenNormal (true);
679  vfh.setUseGivenCentroid (true);
680  vfh.setNormalizeBins (normalize_bins_);
681  output.height = 1;
682 
683  // ---[ Step 1b : check if any dominant cluster was found
684  if (!clusters.empty ())
685  { // ---[ Step 1b.1 : If yes, compute CVFH using the cluster information
686  for (const auto &cluster : clusters) //for each cluster
687  {
688  Eigen::Vector4f avg_normal = Eigen::Vector4f::Zero ();
689  Eigen::Vector4f avg_centroid = Eigen::Vector4f::Zero ();
690 
691  for (const auto &index : cluster.indices)
692  {
693  avg_normal += (*normals_filtered_cloud)[index].getNormalVector4fMap ();
694  avg_centroid += (*normals_filtered_cloud)[index].getVector4fMap ();
695  }
696 
697  avg_normal /= static_cast<float> (cluster.indices.size ());
698  avg_centroid /= static_cast<float> (cluster.indices.size ());
699  avg_normal.normalize ();
700 
701  //append normal and centroid for the clusters
702  dominant_normals_.emplace_back (avg_normal[0], avg_normal[1], avg_normal[2]);
703  centroids_dominant_orientations_.emplace_back (avg_centroid[0], avg_centroid[1], avg_centroid[2]);
704  }
705 
706  //compute modified VFH for all dominant clusters and add them to the list!
707  output.resize (dominant_normals_.size ());
708  output.width = dominant_normals_.size ();
709 
710  for (std::size_t i = 0; i < dominant_normals_.size (); ++i)
711  {
712  //configure VFH computation for CVFH
713  vfh.setNormalToUse (dominant_normals_[i]);
714  vfh.setCentroidToUse (centroids_dominant_orientations_[i]);
716  vfh.compute (vfh_signature);
717  output[i] = vfh_signature[0];
718  }
719 
720  //finish filling the descriptor with the shape distribution
721  PointInTPtr cloud_input (new pcl::PointCloud<PointInT>);
722  pcl::copyPointCloud (*surface_, *indices_, *cloud_input);
723  computeRFAndShapeDistribution (cloud_input, output, clusters_); //this will set transforms_
724  }
725  else
726  { // ---[ Step 1b.1 : If no, compute a VFH using all the object points
727 
728  PCL_WARN("No clusters were found in the surface... using VFH...\n");
729  Eigen::Vector4f avg_centroid;
730  pcl::compute3DCentroid (*surface_, avg_centroid);
731  Eigen::Vector3f cloud_centroid (avg_centroid[0], avg_centroid[1], avg_centroid[2]);
732  centroids_dominant_orientations_.push_back (cloud_centroid);
733 
734  //configure VFH computation using all object points
735  vfh.setCentroidToUse (cloud_centroid);
736  vfh.setUseGivenNormal (false);
737 
739  vfh.compute (vfh_signature);
740 
741  output.resize (1);
742  output.width = 1;
743 
744  output[0] = vfh_signature[0];
745  Eigen::Matrix4f id = Eigen::Matrix4f::Identity ();
746  transforms_.push_back (id);
747  valid_transforms_.push_back (false);
748  }
749 }
750 
751 #define PCL_INSTANTIATE_OURCVFHEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::OURCVFHEstimation<T,NT,OutT>;
752 
753 #endif // PCL_FEATURES_IMPL_OURCVFH_H_
void setInputNormals(const PointCloudNConstPtr &normals)
Provide a pointer to the input dataset that contains the point normals of the XYZ dataset.
Definition: feature.h:339
Feature represents the base feature class.
Definition: feature.h:107
void setRadiusSearch(double radius)
Set the sphere radius that is to be used for determining the nearest neighbors used for the feature e...
Definition: feature.h:198
void setSearchMethod(const KdTreePtr &tree)
Provide a pointer to the search object.
Definition: feature.h:164
void compute(PointCloudOut &output)
Base method for feature estimation for all points given in <setInputCloud (), setIndices ()> using th...
Definition: feature.hpp:194
NormalEstimation estimates local surface properties (surface normals and curvatures)at each 3D point.
Definition: normal_3d.h:244
void setInputCloud(const PointCloudConstPtr &cloud) override
Provide a pointer to the input dataset.
Definition: normal_3d.h:328
OURCVFHEstimation estimates the Oriented, Unique and Repetable Clustered Viewpoint Feature Histogram ...
Definition: our_cvfh.h:60
bool sgurf(Eigen::Vector3f &centroid, Eigen::Vector3f &normal_centroid, PointInTPtr &processed, std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f > > &transformations, PointInTPtr &grid, pcl::PointIndices &indices)
Computes SGURF.
Definition: our_cvfh.hpp:200
void filterNormalsWithHighCurvature(const pcl::PointCloud< PointNT > &cloud, pcl::Indices &indices_to_use, pcl::Indices &indices_out, pcl::Indices &indices_in, float threshold)
Removes normals with high curvature caused by real edges or noisy data.
Definition: our_cvfh.hpp:170
void compute(PointCloudOut &output)
Overloaded computed method from pcl::Feature.
Definition: our_cvfh.hpp:53
typename pcl::PointCloud< PointInT >::Ptr PointInTPtr
Definition: our_cvfh.h:74
void computeRFAndShapeDistribution(PointInTPtr &processed, PointCloudOut &output, std::vector< pcl::PointIndices > &cluster_indices)
Computes SGURF and the shape distribution based on the selected SGURF.
Definition: our_cvfh.hpp:383
virtual void setInputCloud(const PointCloudConstPtr &cloud)
Provide a pointer to the input dataset.
Definition: pcl_base.hpp:65
virtual void setIndices(const IndicesPtr &indices)
Provide a pointer to the vector of indices that represents the input data.
Definition: pcl_base.hpp:72
void push_back(const PointT &pt)
Insert a new point in the cloud, at the end of the container.
Definition: point_cloud.h:663
bool empty() const
Definition: point_cloud.h:446
void resize(std::size_t count)
Resizes the container to contain count elements.
Definition: point_cloud.h:462
std::uint32_t width
The point cloud width (if organized as an image-structure).
Definition: point_cloud.h:398
pcl::PCLHeader header
The point cloud header.
Definition: point_cloud.h:392
std::uint32_t height
The point cloud height (if organized as an image-structure).
Definition: point_cloud.h:400
void clear()
Removes all points in a cloud and sets the width and height to 0.
Definition: point_cloud.h:885
std::size_t size() const
Definition: point_cloud.h:443
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:413
VFHEstimation estimates the Viewpoint Feature Histogram (VFH) descriptor for a given point cloud data...
Definition: vfh.h:73
void setUseGivenNormal(bool use)
Set use_given_normal_.
Definition: vfh.h:142
void setCentroidToUse(const Eigen::Vector3f &centroid)
Set centroid_to_use_.
Definition: vfh.h:171
void compute(PointCloudOut &output)
Overloaded computed method from pcl::Feature.
Definition: vfh.hpp:65
void setNormalToUse(const Eigen::Vector3f &normal)
Set the normal to use.
Definition: vfh.h:152
void setNormalizeBins(bool normalize)
set normalize_bins_
Definition: vfh.h:180
void setUseGivenCentroid(bool use)
Set use_given_centroid_.
Definition: vfh.h:161
search::KdTree is a wrapper class which inherits the pcl::KdTree class for performing search function...
Definition: kdtree.h:62
virtual bool getSortedResults()
Gets whether the results should be sorted (ascending in the distance) or not Otherwise the results ma...
Definition: search.hpp:68
shared_ptr< pcl::search::Search< PointT > > Ptr
Definition: search.h:81
virtual PointCloudConstPtr getInputCloud() const
Get a pointer to the input point cloud dataset.
Definition: search.h:124
virtual int radiusSearch(const PointT &point, double radius, Indices &k_indices, std::vector< float > &k_sqr_distances, unsigned int max_nn=0) const =0
Search for all the nearest neighbors of the query point in a given radius.
Define standard C methods and C++ classes that are common to all methods.
void getMaxDistance(const pcl::PointCloud< PointT > &cloud, const Eigen::Vector4f &pivot_pt, Eigen::Vector4f &max_pt)
Get the point at maximum distance from a given point and a given pointcloud.
Definition: common.hpp:197
void demeanPointCloud(ConstCloudIterator< PointT > &cloud_iterator, const Eigen::Matrix< Scalar, 4, 1 > &centroid, pcl::PointCloud< PointT > &cloud_out, int npts=0)
Subtract a centroid from a point cloud and return the de-meaned representation.
Definition: centroid.hpp:933
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 4, 4 > &transform, bool copy_all_fields)
Apply a rigid transform defined by a 4x4 matrix.
Definition: transforms.hpp:221
unsigned int compute3DCentroid(ConstCloudIterator< PointT > &cloud_iterator, Eigen::Matrix< Scalar, 4, 1 > &centroid)
Compute the 3D (X-Y-Z) centroid of a set of points and return it as a 3D vector.
Definition: centroid.hpp:57
void copyPointCloud(const pcl::PointCloud< PointInT > &cloud_in, pcl::PointCloud< PointOutT > &cloud_out)
Copy all the fields from a given point cloud into a new point cloud.
Definition: io.hpp:142
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:133
::pcl::PCLHeader header
Definition: PointIndices.h:18