Point Cloud Library (PCL)  1.14.1-dev
greedy_verification.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  *
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 #pragma once
38 #include <pcl/recognition/hv/greedy_verification.h>
39 
40 template<typename ModelT, typename SceneT>
41  void
43  {
44  //clear stuff
45  recognition_models_.clear ();
46  points_explained_by_rm_.clear ();
47 
48  // initialize mask...
49  mask_.resize (visible_models_.size ());
50  for (std::size_t i = 0; i < visible_models_.size (); i++)
51  mask_[i] = false;
52 
53  // initialize explained_by_RM
54  points_explained_by_rm_.resize (scene_cloud_downsampled_->size ());
55 
56  // initialize model
57  for (std::size_t m = 0; m < visible_models_.size (); m++)
58  {
59  RecognitionModelPtr recog_model (new RecognitionModel);
60  // voxelize model cloud
61  recog_model->cloud_.reset (new pcl::PointCloud<ModelT>);
62  recog_model->id_ = static_cast<int> (m);
63 
64  pcl::VoxelGrid<ModelT> voxel_grid;
65  voxel_grid.setInputCloud (visible_models_[m]);
66  voxel_grid.setLeafSize (resolution_, resolution_, resolution_);
67  voxel_grid.filter (*(recog_model->cloud_));
68 
69  std::vector<int> explained_indices;
70  std::vector<int> outliers;
71  pcl::Indices nn_indices;
72  std::vector<float> nn_distances;
73 
74  for (std::size_t i = 0; i < recog_model->cloud_->size (); i++)
75  {
76  if (!scene_downsampled_tree_->radiusSearch ((*recog_model->cloud_)[i], inliers_threshold_, nn_indices, nn_distances,
77  std::numeric_limits<int>::max ()))
78  {
79  outliers.push_back (static_cast<int> (i));
80  }
81  else
82  {
83  for (std::size_t k = 0; k < nn_distances.size (); k++)
84  {
85  explained_indices.push_back (nn_indices[k]); //nn_indices[k] points to the scene
86  }
87  }
88  }
89 
90  std::sort (explained_indices.begin (), explained_indices.end ());
91  explained_indices.erase (std::unique (explained_indices.begin (), explained_indices.end ()), explained_indices.end ());
92 
93  recog_model->bad_information_ = static_cast<int> (outliers.size ());
94  recog_model->explained_ = explained_indices;
95  recog_model->good_information_ = static_cast<int> (explained_indices.size ());
96  recog_model->regularizer_ = regularizer_;
97 
98  recognition_models_.push_back (recog_model);
99 
100  for (const int &explained_index : explained_indices)
101  {
102  points_explained_by_rm_[explained_index].push_back (recog_model);
103  }
104  }
105 
106  sortModels ();
107  }
108 
109 template<typename ModelT, typename SceneT>
110  void
112  {
113  initialize ();
114 
115  std::vector<bool> best_solution_;
116  best_solution_.resize (recognition_models_.size ());
117 
118  for (std::size_t i = 0; i < recognition_models_.size (); i++)
119  {
120  if (static_cast<float> (recognition_models_[i]->good_information_) > (regularizer_
121  * static_cast<float> (recognition_models_[i]->bad_information_)))
122  {
123  best_solution_[i] = true;
124  updateGoodInformation (static_cast<int> (i));
125  }
126  else
127  best_solution_[i] = false;
128  }
129 
130  for (std::size_t i = 0; i < best_solution_.size (); i++)
131  {
132  if (best_solution_[i])
133  {
134  mask_[indices_models_[i].index_] = true;
135  }
136  else
137  {
138  mask_[indices_models_[i].index_] = false;
139  }
140  }
141  }
142 
143 #define PCL_INSTANTIATE_GreedyVerification(T1,T2) template class PCL_EXPORTS pcl::GreedyVerification<T1,T2>;
void filter(PointCloud &output)
Calls the filtering method and returns the filtered dataset in output.
Definition: filter.h:121
A greedy hypothesis verification method.
void verify() override
Starts verification.
virtual void setInputCloud(const PointCloudConstPtr &cloud)
Provide a pointer to the input dataset.
Definition: pcl_base.hpp:65
VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data.
Definition: voxel_grid.h:210
void setLeafSize(const Eigen::Vector4f &leaf_size)
Set the voxel grid leaf size.
Definition: voxel_grid.h:247
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:133