Point Cloud Library (PCL)  1.15.1-dev
hv_go.hpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2012 Aitor Aldoma, Federico Tombari
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 Willow Garage, Inc. 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 #ifndef PCL_RECOGNITION_IMPL_HV_GO_HPP_
38 #define PCL_RECOGNITION_IMPL_HV_GO_HPP_
39 
40 #include <pcl/recognition/hv/hv_go.h>
41 #include <pcl/common/common.h> // for getMinMax3D
42 #include <pcl/common/time.h>
43 #include <pcl/point_types.h>
44 
45 #include <memory>
46 #include <numeric>
47 
48 template<typename PointT, typename NormalT>
49 inline void extractEuclideanClustersSmooth(const typename pcl::PointCloud<PointT> &cloud, const typename pcl::PointCloud<NormalT> &normals, float tolerance,
50  const typename pcl::search::Search<PointT>::Ptr &tree, std::vector<pcl::PointIndices> &clusters, double eps_angle, float curvature_threshold,
51  unsigned int min_pts_per_cluster, unsigned int max_pts_per_cluster = (std::numeric_limits<int>::max) ())
52 {
53 
54  if (tree->getInputCloud ()->size () != cloud.size ())
55  {
56  PCL_ERROR("[pcl::extractEuclideanClusters] Tree built for a different point cloud dataset\n");
57  return;
58  }
59  if (cloud.size () != normals.size ())
60  {
61  PCL_ERROR("[pcl::extractEuclideanClusters] Number of points in the input point cloud different than normals!\n");
62  return;
63  }
64  // If tree gives sorted results, we can skip the first one because it is the query point itself
65  const std::size_t nn_start_idx = tree->getSortedResults () ? 1 : 0;
66 
67  // Create a bool vector of processed point indices, and initialize it to false
68  std::vector<bool> processed (cloud.size (), false);
69 
70  pcl::Indices nn_indices;
71  std::vector<float> nn_distances;
72  // Process all points in the indices vector
73  int size = static_cast<int> (cloud.size ());
74  for (int i = 0; i < size; ++i)
75  {
76  if (processed[i])
77  continue;
78 
79  std::vector<unsigned int> seed_queue;
80  int sq_idx = 0;
81  seed_queue.push_back (i);
82 
83  processed[i] = true;
84 
85  while (sq_idx < static_cast<int> (seed_queue.size ()))
86  {
87 
88  if (normals[seed_queue[sq_idx]].curvature > curvature_threshold)
89  {
90  sq_idx++;
91  continue;
92  }
93 
94  // Search for sq_idx
95  if (!tree->radiusSearch (seed_queue[sq_idx], tolerance, nn_indices, nn_distances))
96  {
97  sq_idx++;
98  continue;
99  }
100 
101  for (std::size_t j = nn_start_idx; j < nn_indices.size (); ++j)
102  {
103  if (processed[nn_indices[j]]) // Has this point been processed before ?
104  continue;
105 
106  if (normals[nn_indices[j]].curvature > curvature_threshold)
107  {
108  continue;
109  }
110 
111  //processed[nn_indices[j]] = true;
112  // [-1;1]
113 
114  double dot_p = normals[seed_queue[sq_idx]].normal[0] * normals[nn_indices[j]].normal[0]
115  + normals[seed_queue[sq_idx]].normal[1] * normals[nn_indices[j]].normal[1]
116  + normals[seed_queue[sq_idx]].normal[2] * normals[nn_indices[j]].normal[2];
117 
118  if (std::abs (std::acos (dot_p)) < eps_angle)
119  {
120  processed[nn_indices[j]] = true;
121  seed_queue.push_back (nn_indices[j]);
122  }
123  }
124 
125  sq_idx++;
126  }
127 
128  // If this queue is satisfactory, add to the clusters
129  if (seed_queue.size () >= min_pts_per_cluster && seed_queue.size () <= max_pts_per_cluster)
130  {
132  r.indices.resize (seed_queue.size ());
133  for (std::size_t j = 0; j < seed_queue.size (); ++j)
134  r.indices[j] = seed_queue[j];
135 
136  std::sort (r.indices.begin (), r.indices.end ());
137  r.indices.erase (std::unique (r.indices.begin (), r.indices.end ()), r.indices.end ());
138 
139  r.header = cloud.header;
140  clusters.push_back (r); // We could avoid a copy by working directly in the vector
141  }
142  }
143 }
144 
145 template<typename ModelT, typename SceneT>
146 mets::gol_type pcl::GlobalHypothesesVerification<ModelT, SceneT>::evaluateSolution(const std::vector<bool> & active, int changed)
147 {
148  float sign = 1.f;
149  //update explained_by_RM
150  if (active[changed])
151  {
152  //it has been activated
153  updateExplainedVector (recognition_models_[changed]->explained_, recognition_models_[changed]->explained_distances_, explained_by_RM_,
154  explained_by_RM_distance_weighted, 1.f);
155  updateUnexplainedVector (recognition_models_[changed]->unexplained_in_neighborhood, recognition_models_[changed]->unexplained_in_neighborhood_weights,
156  unexplained_by_RM_neighboorhods, recognition_models_[changed]->explained_, explained_by_RM_, 1.f);
157  updateCMDuplicity(recognition_models_[changed]->complete_cloud_occupancy_indices_, complete_cloud_occupancy_by_RM_, 1.f);
158  } else
159  {
160  //it has been deactivated
161  updateExplainedVector (recognition_models_[changed]->explained_, recognition_models_[changed]->explained_distances_, explained_by_RM_,
162  explained_by_RM_distance_weighted, -1.f);
163  updateUnexplainedVector (recognition_models_[changed]->unexplained_in_neighborhood, recognition_models_[changed]->unexplained_in_neighborhood_weights,
164  unexplained_by_RM_neighboorhods, recognition_models_[changed]->explained_, explained_by_RM_, -1.f);
165  updateCMDuplicity(recognition_models_[changed]->complete_cloud_occupancy_indices_, complete_cloud_occupancy_by_RM_, -1.f);
166  sign = -1.f;
167  }
168 
169  int duplicity = getDuplicity ();
170  float good_info = getExplainedValue ();
171 
172  float unexplained_info = getPreviousUnexplainedValue ();
173  float bad_info = static_cast<float> (getPreviousBadInfo ())
174  + (recognition_models_[changed]->outliers_weight_ * static_cast<float> (recognition_models_[changed]->bad_information_)) * sign;
175 
176  setPreviousBadInfo (bad_info);
177 
178  int n_active_hyp = 0;
179  for(const bool i : active) {
180  if(i)
181  n_active_hyp++;
182  }
183 
184  float duplicity_cm = static_cast<float> (getDuplicityCM ()) * w_occupied_multiple_cm_;
185  return static_cast<mets::gol_type> ((good_info - bad_info - static_cast<float> (duplicity) - unexplained_info - duplicity_cm - static_cast<float> (n_active_hyp)) * -1.f); //return the dual to our max problem
186 }
187 
188 ///////////////////////////////////////////////////////////////////////////////////////////////////
189 template<typename ModelT, typename SceneT>
191 {
192  //clear stuff
193  recognition_models_.clear ();
194  unexplained_by_RM_neighboorhods.clear ();
195  explained_by_RM_distance_weighted.clear ();
196  explained_by_RM_.clear ();
197  mask_.clear ();
198  indices_.clear (),
199  complete_cloud_occupancy_by_RM_.clear ();
200 
201  // initialize mask to false
202  mask_.resize (complete_models_.size ());
203  for (std::size_t i = 0; i < complete_models_.size (); i++)
204  mask_[i] = false;
205 
206  indices_.resize (complete_models_.size ());
207 
208  NormalEstimator_ n3d;
209  scene_normals_.reset (new pcl::PointCloud<pcl::Normal> ());
210 
211  n3d.setRadiusSearch (radius_normals_);
212  n3d.setInputCloud (scene_cloud_downsampled_);
213  n3d.compute (*scene_normals_);
214 
215  //check nans...
216  int j = 0;
217  for (std::size_t i = 0; i < scene_normals_->size (); ++i)
218  {
219  if (!std::isfinite ((*scene_normals_)[i].normal_x) || !std::isfinite ((*scene_normals_)[i].normal_y)
220  || !std::isfinite ((*scene_normals_)[i].normal_z))
221  continue;
222 
223  (*scene_normals_)[j] = (*scene_normals_)[i];
224  (*scene_cloud_downsampled_)[j] = (*scene_cloud_downsampled_)[i];
225 
226  j++;
227  }
228 
229  scene_normals_->points.resize (j);
230  scene_normals_->width = j;
231  scene_normals_->height = 1;
232 
233  scene_cloud_downsampled_->points.resize (j);
234  scene_cloud_downsampled_->width = j;
235  scene_cloud_downsampled_->height = 1;
236 
237  explained_by_RM_.resize (scene_cloud_downsampled_->size (), 0);
238  explained_by_RM_distance_weighted.resize (scene_cloud_downsampled_->size (), 0.f);
239  unexplained_by_RM_neighboorhods.resize (scene_cloud_downsampled_->size (), 0.f);
240 
241  //compute segmentation of the scene if detect_clutter_
242  if (detect_clutter_)
243  {
244  //initialize kdtree for search
245  scene_downsampled_tree_.reset (new pcl::search::KdTree<SceneT>);
246  scene_downsampled_tree_->setInputCloud (scene_cloud_downsampled_);
247 
248  std::vector<pcl::PointIndices> clusters;
249  double eps_angle_threshold = 0.2;
250  int min_points = 20;
251  float curvature_threshold = 0.045f;
252 
253  extractEuclideanClustersSmooth<SceneT, pcl::Normal> (*scene_cloud_downsampled_, *scene_normals_, inliers_threshold_ * 2.f, scene_downsampled_tree_,
254  clusters, eps_angle_threshold, curvature_threshold, min_points);
255 
256  clusters_cloud_.reset (new pcl::PointCloud<pcl::PointXYZI>);
257  clusters_cloud_->points.resize (scene_cloud_downsampled_->size ());
258  clusters_cloud_->width = scene_cloud_downsampled_->width;
259  clusters_cloud_->height = 1;
260 
261  for (std::size_t i = 0; i < scene_cloud_downsampled_->size (); i++)
262  {
263  pcl::PointXYZI p;
264  p.getVector3fMap () = (*scene_cloud_downsampled_)[i].getVector3fMap ();
265  p.intensity = 0.f;
266  (*clusters_cloud_)[i] = p;
267  }
268 
269  float intens_incr = 100.f / static_cast<float> (clusters.size ());
270  float intens = intens_incr;
271  for (const auto &cluster : clusters)
272  {
273  for (const auto &vertex : cluster.indices)
274  {
275  (*clusters_cloud_)[vertex].intensity = intens;
276  }
277 
278  intens += intens_incr;
279  }
280  }
281 
282  //compute cues
283  {
284  pcl::ScopeTime tcues ("Computing cues");
285  recognition_models_.resize (complete_models_.size ());
286  int valid = 0;
287  for (int i = 0; i < static_cast<int> (complete_models_.size ()); i++)
288  {
289  //create recognition model
290  recognition_models_[valid].reset (new RecognitionModel ());
291  if(addModel (visible_models_[i], complete_models_[i], recognition_models_[valid])) {
292  indices_[valid] = i;
293  valid++;
294  }
295  }
296 
297  recognition_models_.resize(valid);
298  indices_.resize(valid);
299  }
300 
301  //compute the bounding boxes for the models
302  ModelT min_pt_all, max_pt_all;
303  min_pt_all.x = min_pt_all.y = min_pt_all.z = std::numeric_limits<float>::max ();
304  max_pt_all.x = max_pt_all.y = max_pt_all.z = (std::numeric_limits<float>::max () - 0.001f) * -1;
305 
306  for (std::size_t i = 0; i < recognition_models_.size (); i++)
307  {
308  ModelT min_pt, max_pt;
309  pcl::getMinMax3D (*complete_models_[indices_[i]], min_pt, max_pt);
310  if (min_pt.x < min_pt_all.x)
311  min_pt_all.x = min_pt.x;
312 
313  if (min_pt.y < min_pt_all.y)
314  min_pt_all.y = min_pt.y;
315 
316  if (min_pt.z < min_pt_all.z)
317  min_pt_all.z = min_pt.z;
318 
319  if (max_pt.x > max_pt_all.x)
320  max_pt_all.x = max_pt.x;
321 
322  if (max_pt.y > max_pt_all.y)
323  max_pt_all.y = max_pt.y;
324 
325  if (max_pt.z > max_pt_all.z)
326  max_pt_all.z = max_pt.z;
327  }
328 
329  int size_x, size_y, size_z;
330  size_x = static_cast<int> (std::ceil (std::abs (max_pt_all.x - min_pt_all.x) / res_occupancy_grid_)) + 1;
331  size_y = static_cast<int> (std::ceil (std::abs (max_pt_all.y - min_pt_all.y) / res_occupancy_grid_)) + 1;
332  size_z = static_cast<int> (std::ceil (std::abs (max_pt_all.z - min_pt_all.z) / res_occupancy_grid_)) + 1;
333 
334  complete_cloud_occupancy_by_RM_.resize (size_x * size_y * size_z, 0);
335 
336  for (std::size_t i = 0; i < recognition_models_.size (); i++)
337  {
338 
339  std::map<int, bool> banned;
340  std::map<int, bool>::iterator banned_it;
341 
342  for (const auto& point: *complete_models_[indices_[i]])
343  {
344  const int pos_x = static_cast<int> (std::floor ((point.x - min_pt_all.x) / res_occupancy_grid_));
345  const int pos_y = static_cast<int> (std::floor ((point.y - min_pt_all.y) / res_occupancy_grid_));
346  const int pos_z = static_cast<int> (std::floor ((point.z - min_pt_all.z) / res_occupancy_grid_));
347 
348  const int idx = pos_z * size_x * size_y + pos_y * size_x + pos_x;
349  banned_it = banned.find (idx);
350  if (banned_it == banned.end ())
351  {
352  complete_cloud_occupancy_by_RM_[idx]++;
353  recognition_models_[i]->complete_cloud_occupancy_indices_.push_back (idx);
354  banned[idx] = true;
355  }
356  }
357  }
358 
359  {
360  pcl::ScopeTime tcues ("Computing clutter cues");
361 #pragma omp parallel for \
362  default(none) \
363  schedule(dynamic, 4) \
364  num_threads(omp_get_num_procs())
365  for (int j = 0; j < static_cast<int> (recognition_models_.size ()); j++)
366  computeClutterCue (recognition_models_[j]);
367  }
368 
369  cc_.clear ();
370  n_cc_ = 1;
371  cc_.resize (n_cc_);
372  for (std::size_t i = 0; i < recognition_models_.size (); i++)
373  cc_[0].push_back (static_cast<int> (i));
374 
375 }
376 
377 template<typename ModelT, typename SceneT>
378 void pcl::GlobalHypothesesVerification<ModelT, SceneT>::SAOptimize(std::vector<int> & cc_indices, std::vector<bool> & initial_solution)
379 {
380 
381  //temporal copy of recogniton_models_
382  std::vector<RecognitionModelPtr> recognition_models_copy;
383  recognition_models_copy = recognition_models_;
384 
385  recognition_models_.clear ();
386 
387  for (const int &cc_index : cc_indices)
388  {
389  recognition_models_.push_back (recognition_models_copy[cc_index]);
390  }
391 
392  for (std::size_t j = 0; j < recognition_models_.size (); j++)
393  {
394  RecognitionModelPtr recog_model = recognition_models_[j];
395  for (std::size_t i = 0; i < recog_model->explained_.size (); i++)
396  {
397  explained_by_RM_[recog_model->explained_[i]]++;
398  explained_by_RM_distance_weighted[recog_model->explained_[i]] += recog_model->explained_distances_[i];
399  }
400 
401  if (detect_clutter_)
402  {
403  for (std::size_t i = 0; i < recog_model->unexplained_in_neighborhood.size (); i++)
404  {
405  unexplained_by_RM_neighboorhods[recog_model->unexplained_in_neighborhood[i]] += recog_model->unexplained_in_neighborhood_weights[i];
406  }
407  }
408  }
409 
410  int occupied_multiple = 0;
411  for(const auto& i : complete_cloud_occupancy_by_RM_) {
412  if(i > 1) {
413  occupied_multiple+=i;
414  }
415  }
416 
417  setPreviousDuplicityCM(occupied_multiple);
418  //do optimization
419  //Define model SAModel, initial solution is all models activated
420 
421  int duplicity;
422  float good_information_ = getTotalExplainedInformation (explained_by_RM_, explained_by_RM_distance_weighted, &duplicity);
423  float bad_information_ = 0;
424  float unexplained_in_neighboorhod = getUnexplainedInformationInNeighborhood (unexplained_by_RM_neighboorhods, explained_by_RM_);
425 
426  for (std::size_t i = 0; i < initial_solution.size (); i++)
427  {
428  if (initial_solution[i])
429  bad_information_ += recognition_models_[i]->outliers_weight_ * static_cast<float> (recognition_models_[i]->bad_information_);
430  }
431 
432  setPreviousExplainedValue (good_information_);
433  setPreviousDuplicity (duplicity);
434  setPreviousBadInfo (bad_information_);
435  setPreviousUnexplainedValue (unexplained_in_neighboorhod);
436 
437  SAModel model;
438  model.cost_ = static_cast<mets::gol_type> ((good_information_ - bad_information_
439  - static_cast<float> (duplicity)
440  - static_cast<float> (occupied_multiple) * w_occupied_multiple_cm_
441  - static_cast<float> (recognition_models_.size ())
442  - unexplained_in_neighboorhod) * -1.f);
443 
444  model.setSolution (initial_solution);
445  model.setOptimizer (this);
446  SAModel best (model);
447 
448  move_manager neigh (static_cast<int> (cc_indices.size ()));
449 
450  mets::best_ever_solution best_recorder (best);
451  mets::noimprove_termination_criteria noimprove (max_iterations_);
452  mets::linear_cooling linear_cooling;
453  mets::simulated_annealing<move_manager> sa (model, best_recorder, neigh, noimprove, linear_cooling, initial_temp_, 1e-7, 2);
454  sa.setApplyAndEvaluate(true);
455 
456  {
457  pcl::ScopeTime t ("SA search...");
458  sa.search ();
459  }
460 
461  best_seen_ = static_cast<const SAModel&> (best_recorder.best_seen ());
462  for (std::size_t i = 0; i < best_seen_.solution_.size (); i++)
463  {
464  initial_solution[i] = best_seen_.solution_[i];
465  }
466 
467  recognition_models_ = recognition_models_copy;
468 
469 }
470 
471 ///////////////////////////////////////////////////////////////////////////////////////////////////
472 template<typename ModelT, typename SceneT>
474 {
475  initialize ();
476 
477  //for each connected component, find the optimal solution
478  for (int c = 0; c < n_cc_; c++)
479  {
480  //TODO: Check for trivial case...
481  //TODO: Check also the number of hypotheses and use exhaustive enumeration if smaller than 10
482  std::vector<bool> subsolution (cc_[c].size (), true);
483  SAOptimize (cc_[c], subsolution);
484  for (std::size_t i = 0; i < subsolution.size (); i++)
485  {
486  mask_[indices_[cc_[c][i]]] = (subsolution[i]);
487  }
488  }
489 }
490 
491 template<typename ModelT, typename SceneT>
493  typename pcl::PointCloud<ModelT>::ConstPtr & complete_model, RecognitionModelPtr & recog_model)
494 {
495  //voxelize model cloud
496  recog_model->cloud_.reset (new pcl::PointCloud<ModelT> ());
497  recog_model->complete_cloud_.reset (new pcl::PointCloud<ModelT> ());
498 
499  float size_model = resolution_;
500  pcl::VoxelGrid<ModelT> voxel_grid;
501  voxel_grid.setInputCloud (model);
502  voxel_grid.setLeafSize (size_model, size_model, size_model);
503  voxel_grid.filter (*(recog_model->cloud_));
504 
505  pcl::VoxelGrid<ModelT> voxel_grid2;
506  voxel_grid2.setInputCloud (complete_model);
507  voxel_grid2.setLeafSize (size_model, size_model, size_model);
508  voxel_grid2.filter (*(recog_model->complete_cloud_));
509 
510  {
511  //check nans...
512  int j = 0;
513  for (auto& point: *(recog_model->cloud_))
514  {
515  if (!isXYZFinite (point))
516  continue;
517 
518  (*recog_model->cloud_)[j] = point;
519  j++;
520  }
521 
522  recog_model->cloud_->points.resize (j);
523  recog_model->cloud_->width = j;
524  recog_model->cloud_->height = 1;
525  }
526 
527  if (recog_model->cloud_->points.empty ())
528  {
529  PCL_WARN("The model cloud has no points..\n");
530  return false;
531  }
532 
533  //compute normals unless given (now do it always...)
535  recog_model->normals_.reset (new pcl::PointCloud<pcl::Normal> ());
536  n3d.setRadiusSearch (radius_normals_);
537  n3d.setInputCloud ((recog_model->cloud_));
538  n3d.compute (*(recog_model->normals_));
539 
540  //check nans...
541  int j = 0;
542  for (std::size_t i = 0; i < recog_model->normals_->size (); ++i)
543  {
544  if (isNormalFinite((*recog_model->normals_)[i]))
545  continue;
546 
547  (*recog_model->normals_)[j] = (*recog_model->normals_)[i];
548  (*recog_model->cloud_)[j] = (*recog_model->cloud_)[i];
549  j++;
550  }
551 
552  recog_model->normals_->points.resize (j);
553  recog_model->normals_->width = j;
554  recog_model->normals_->height = 1;
555 
556  recog_model->cloud_->points.resize (j);
557  recog_model->cloud_->width = j;
558  recog_model->cloud_->height = 1;
559 
560  std::vector<int> explained_indices;
561  std::vector<float> outliers_weight;
562  std::vector<float> explained_indices_distances;
563 
564  pcl::Indices nn_indices;
565  std::vector<float> nn_distances;
566 
567  std::map<int, std::shared_ptr<std::vector<std::pair<int, float>>>> model_explains_scene_points; //which point i from the scene is explained by a points j_k with dist d_k from the model
568 
569  outliers_weight.resize (recog_model->cloud_->size ());
570  recog_model->outlier_indices_.resize (recog_model->cloud_->size ());
571 
572  std::size_t o = 0;
573  for (std::size_t i = 0; i < recog_model->cloud_->size (); i++)
574  {
575  if (!scene_downsampled_tree_->radiusSearch ((*recog_model->cloud_)[i], inliers_threshold_, nn_indices, nn_distances, std::numeric_limits<int>::max ()))
576  {
577  //outlier
578  outliers_weight[o] = regularizer_;
579  recog_model->outlier_indices_[o] = static_cast<int> (i);
580  o++;
581  } else
582  {
583  for (std::size_t k = 0; k < nn_distances.size (); k++)
584  {
585  std::pair<int, float> pair = std::make_pair (i, nn_distances[k]); //i is a index to a model point and then distance
586  auto it = model_explains_scene_points.find (nn_indices[k]);
587  if (it == model_explains_scene_points.end ())
588  {
589  std::shared_ptr<std::vector<std::pair<int, float>>> vec (new std::vector<std::pair<int, float>> ());
590  vec->push_back (pair);
591  model_explains_scene_points[nn_indices[k]] = vec;
592  } else
593  {
594  it->second->push_back (pair);
595  }
596  }
597  }
598  }
599 
600  outliers_weight.resize (o);
601  recog_model->outlier_indices_.resize (o);
602 
603  recog_model->outliers_weight_ = (std::accumulate (outliers_weight.begin (), outliers_weight.end (), 0.f) / static_cast<float> (outliers_weight.size ()));
604  if (outliers_weight.empty ())
605  recog_model->outliers_weight_ = 1.f;
606 
607  pcl::IndicesPtr indices_scene (new pcl::Indices);
608  //go through the map and keep the closest model point in case that several model points explain a scene point
609 
610  int p = 0;
611 
612  for (auto it = model_explains_scene_points.cbegin (); it != model_explains_scene_points.cend (); it++, p++)
613  {
614  std::size_t closest = 0;
615  float min_d = std::numeric_limits<float>::min ();
616  for (std::size_t i = 0; i < it->second->size (); i++)
617  {
618  if (it->second->at (i).second > min_d)
619  {
620  min_d = it->second->at (i).second;
621  closest = i;
622  }
623  }
624 
625  float d = it->second->at (closest).second;
626  float d_weight = -(d * d / (inliers_threshold_)) + 1;
627 
628  //it->first is index to scene point
629  //using normals to weight inliers
630  Eigen::Vector3f scene_p_normal = (*scene_normals_)[it->first].getNormalVector3fMap ();
631  Eigen::Vector3f model_p_normal =
632  (*recog_model->normals_)[it->second->at(closest).first].getNormalVector3fMap();
633  float dotp = scene_p_normal.dot (model_p_normal) * 1.f; //[-1,1] from antiparallel through perpendicular to parallel
634 
635  if (dotp < 0.f)
636  dotp = 0.f;
637 
638  explained_indices.push_back (it->first);
639  explained_indices_distances.push_back (d_weight * dotp);
640 
641  }
642 
643  recog_model->bad_information_ = static_cast<int> (recog_model->outlier_indices_.size ());
644  recog_model->explained_ = explained_indices;
645  recog_model->explained_distances_ = explained_indices_distances;
646 
647  return true;
648 }
649 
650 template<typename ModelT, typename SceneT>
651 void pcl::GlobalHypothesesVerification<ModelT, SceneT>::computeClutterCue(RecognitionModelPtr & recog_model)
652 {
653  if (detect_clutter_)
654  {
655 
656  float rn_sqr = radius_neighborhood_GO_ * radius_neighborhood_GO_;
657  pcl::Indices nn_indices;
658  std::vector<float> nn_distances;
659 
660  std::vector < std::pair<int, int> > neighborhood_indices; //first is indices to scene point and second is indices to explained_ scene points
661  for (pcl::index_t i = 0; i < static_cast<pcl::index_t> (recog_model->explained_.size ()); i++)
662  {
663  if (scene_downsampled_tree_->radiusSearch ((*scene_cloud_downsampled_)[recog_model->explained_[i]], radius_neighborhood_GO_, nn_indices,
664  nn_distances, std::numeric_limits<int>::max ()))
665  {
666  for (std::size_t k = 0; k < nn_distances.size (); k++)
667  {
668  if (nn_indices[k] != i)
669  neighborhood_indices.emplace_back (nn_indices[k], i);
670  }
671  }
672  }
673 
674  //sort neighborhood indices by id
675  std::sort (neighborhood_indices.begin (), neighborhood_indices.end (),
676  [] (const auto& p1, const auto& p2) { return p1.first < p2.first; });
677 
678  //erase duplicated unexplained points
679  neighborhood_indices.erase (
680  std::unique (neighborhood_indices.begin (), neighborhood_indices.end (),
681  [] (const auto& p1, const auto& p2) { return p1.first == p2.first; }), neighborhood_indices.end ());
682 
683  //sort explained points
684  std::vector<int> exp_idces (recog_model->explained_);
685  std::sort (exp_idces.begin (), exp_idces.end ());
686 
687  recog_model->unexplained_in_neighborhood.resize (neighborhood_indices.size ());
688  recog_model->unexplained_in_neighborhood_weights.resize (neighborhood_indices.size ());
689 
690  std::size_t p = 0;
691  std::size_t j = 0;
692  for (const auto &neighborhood_index : neighborhood_indices)
693  {
694  if ((j < exp_idces.size ()) && (neighborhood_index.first == exp_idces[j]))
695  {
696  //this index is explained by the hypothesis so ignore it, advance j
697  j++;
698  } else
699  {
700  //indices_in_nb[i] < exp_idces[j]
701  //recog_model->unexplained_in_neighborhood.push_back(neighborhood_indices[i]);
702  recog_model->unexplained_in_neighborhood[p] = neighborhood_index.first;
703 
704  if ((*clusters_cloud_)[recog_model->explained_[neighborhood_index.second]].intensity != 0.f
705  && ((*clusters_cloud_)[recog_model->explained_[neighborhood_index.second]].intensity
706  == (*clusters_cloud_)[neighborhood_index.first].intensity))
707  {
708 
709  recog_model->unexplained_in_neighborhood_weights[p] = clutter_regularizer_;
710 
711  } else
712  {
713  //neighborhood_indices[i].first gives the index to the scene point and second to the explained scene point by the model causing this...
714  //calculate weight of this clutter point based on the distance of the scene point and the model point causing it
715  float d = static_cast<float> (pow (
716  ((*scene_cloud_downsampled_)[recog_model->explained_[neighborhood_index.second]].getVector3fMap ()
717  - (*scene_cloud_downsampled_)[neighborhood_index.first].getVector3fMap ()).norm (), 2));
718  float d_weight = -(d / rn_sqr) + 1; //points that are close have a strong weight*/
719 
720  //using normals to weight clutter points
721  Eigen::Vector3f scene_p_normal = (*scene_normals_)[neighborhood_index.first].getNormalVector3fMap ();
722  Eigen::Vector3f model_p_normal = (*scene_normals_)[recog_model->explained_[neighborhood_index.second]].getNormalVector3fMap ();
723  float dotp = scene_p_normal.dot (model_p_normal); //[-1,1] from antiparallel through perpendicular to parallel
724 
725  if (dotp < 0)
726  dotp = 0.f;
727 
728  recog_model->unexplained_in_neighborhood_weights[p] = d_weight * dotp;
729  }
730  p++;
731  }
732  }
733 
734  recog_model->unexplained_in_neighborhood_weights.resize (p);
735  recog_model->unexplained_in_neighborhood.resize (p);
736  }
737 }
738 
739 #define PCL_INSTANTIATE_GoHV(T1,T2) template class PCL_EXPORTS pcl::GlobalHypothesesVerification<T1,T2>;
740 
741 #endif /* PCL_RECOGNITION_IMPL_HV_GO_HPP_ */
742 
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 compute(PointCloudOut &output)
Base method for feature estimation for all points given in <setInputCloud (), setIndices ()> using th...
Definition: feature.hpp:195
void filter(PointCloud &output)
Calls the filtering method and returns the filtered dataset in output.
Definition: filter.h:121
A hypothesis verification method proposed in "A Global Hypotheses Verification Method for 3D Object R...
Definition: hv_go.h:37
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
virtual void setInputCloud(const PointCloudConstPtr &cloud)
Provide a pointer to the input dataset.
Definition: pcl_base.hpp:65
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: point_cloud.h:174
void push_back(const PointT &pt)
Insert a new point in the cloud, at the end of the container.
Definition: point_cloud.h:664
pcl::PCLHeader header
The point cloud header.
Definition: point_cloud.h:393
std::size_t size() const
Definition: point_cloud.h:444
shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:415
Class to measure the time spent in a scope.
Definition: time.h:106
VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data.
Definition: voxel_grid.h:222
void setLeafSize(const Eigen::Vector4f &leaf_size)
Set the voxel grid leaf size.
Definition: voxel_grid.h:259
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.
Defines all the PCL implemented PointT point type structures.
Define methods for measuring time spent in code blocks.
void getMinMax3D(const pcl::PointCloud< PointT > &cloud, PointT &min_pt, PointT &max_pt)
Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud.
Definition: common.hpp:295
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
shared_ptr< Indices > IndicesPtr
Definition: pcl_base.h:58
constexpr bool isNormalFinite(const PointT &) noexcept
Definition: point_tests.h:132
::pcl::PCLHeader header
Definition: PointIndices.h:18