Point Cloud Library (PCL)  1.14.0-dev
sift_keypoint.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 
38 #ifndef PCL_SIFT_KEYPOINT_IMPL_H_
39 #define PCL_SIFT_KEYPOINT_IMPL_H_
40 
41 #include <pcl/keypoints/sift_keypoint.h>
42 #include <pcl/common/io.h>
43 #include <pcl/filters/voxel_grid.h>
44 
45 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
46 template <typename PointInT, typename PointOutT> void
47 pcl::SIFTKeypoint<PointInT, PointOutT>::setScales (float min_scale, int nr_octaves, int nr_scales_per_octave)
48 {
49  min_scale_ = min_scale;
50  nr_octaves_ = nr_octaves;
51  nr_scales_per_octave_ = nr_scales_per_octave;
52 }
53 
54 
55 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
56 template <typename PointInT, typename PointOutT> void
58 {
59  min_contrast_ = min_contrast;
60 }
61 
62 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
63 template <typename PointInT, typename PointOutT> bool
65 {
66  if (min_scale_ <= 0)
67  {
68  PCL_ERROR ("[pcl::%s::initCompute] : Minimum scale (%f) must be strict positive!\n",
69  name_.c_str (), min_scale_);
70  return (false);
71  }
72  if (nr_octaves_ < 1)
73  {
74  PCL_ERROR ("[pcl::%s::initCompute] : Number of octaves (%d) must be at least 1!\n",
75  name_.c_str (), nr_octaves_);
76  return (false);
77  }
78  if (nr_scales_per_octave_ < 1)
79  {
80  PCL_ERROR ("[pcl::%s::initCompute] : Number of scales per octave (%d) must be at least 1!\n",
81  name_.c_str (), nr_scales_per_octave_);
82  return (false);
83  }
84  if (min_contrast_ < 0)
85  {
86  PCL_ERROR ("[pcl::%s::initCompute] : Minimum contrast (%f) must be non-negative!\n",
87  name_.c_str (), min_contrast_);
88  return (false);
89  }
90 
91  this->setKSearch (1);
92  tree_.reset (new pcl::search::KdTree<PointInT> (true));
93  return (true);
94 }
95 
96 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
97 template <typename PointInT, typename PointOutT> void
99 {
100  if (surface_ && surface_ != input_)
101  {
102  PCL_WARN ("[pcl::%s::detectKeypoints] : ", name_.c_str ());
103  PCL_WARN ("A search surface has been set by setSearchSurface, but this SIFT keypoint detection algorithm does ");
104  PCL_WARN ("not support search surfaces other than the input cloud. ");
105  PCL_WARN ("The cloud provided in setInputCloud is being used instead.\n");
106  }
107 
108  // Check if the output has a "scale" field
109  scale_idx_ = pcl::getFieldIndex<PointOutT> ("scale", out_fields_);
110 
111  // Make sure the output cloud is empty
112  output.clear ();
113 
114  // Create a local copy of the input cloud that will be resized for each octave
115  typename pcl::PointCloud<PointInT>::Ptr cloud (new pcl::PointCloud<PointInT> (*input_));
116 
117  VoxelGrid<PointInT> voxel_grid;
118  // Search for keypoints at each octave
119  float scale = min_scale_;
120  for (int i_octave = 0; i_octave < nr_octaves_; ++i_octave)
121  {
122  // Downsample the point cloud
123  const float s = 1.0f * scale; // note: this can be adjusted
124  voxel_grid.setLeafSize (s, s, s);
125  voxel_grid.setInputCloud (cloud);
127  voxel_grid.filter (*temp);
128  cloud = temp;
129 
130  // Make sure the downsampled cloud still has enough points
131  constexpr std::size_t min_nr_points = 25;
132  if (cloud->size () < min_nr_points)
133  break;
134 
135  // Update the KdTree with the downsampled points
136  tree_->setInputCloud (cloud);
137 
138  // Detect keypoints for the current scale
139  detectKeypointsForOctave (*cloud, *tree_, scale, nr_scales_per_octave_, output);
140 
141  // Increase the scale by another octave
142  scale *= 2;
143  }
144 
145  // Set final properties
146  output.height = 1;
147  output.width = output.size ();
148  output.header = input_->header;
149  output.sensor_origin_ = input_->sensor_origin_;
150  output.sensor_orientation_ = input_->sensor_orientation_;
151 }
152 
153 
154 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
155 template <typename PointInT, typename PointOutT> void
157  const PointCloudIn &input, KdTree &tree, float base_scale, int nr_scales_per_octave,
158  PointCloudOut &output)
159 {
160  // Compute the difference of Gaussians (DoG) scale space
161  std::vector<float> scales (nr_scales_per_octave + 3);
162  for (int i_scale = 0; i_scale <= nr_scales_per_octave + 2; ++i_scale)
163  {
164  scales[i_scale] = base_scale * powf (2.0f, (1.0f * static_cast<float> (i_scale) - 1.0f) / static_cast<float> (nr_scales_per_octave));
165  }
166  Eigen::MatrixXf diff_of_gauss;
167  computeScaleSpace (input, tree, scales, diff_of_gauss);
168 
169  // Find extrema in the DoG scale space
170  pcl::Indices extrema_indices;
171  std::vector<int> extrema_scales;
172  findScaleSpaceExtrema (input, tree, diff_of_gauss, extrema_indices, extrema_scales);
173 
174  output.reserve (output.size () + extrema_indices.size ());
175  // Save scale?
176  if (scale_idx_ != -1)
177  {
178  // Add keypoints to output
179  for (std::size_t i_keypoint = 0; i_keypoint < extrema_indices.size (); ++i_keypoint)
180  {
181  PointOutT keypoint;
182  const auto &keypoint_index = extrema_indices[i_keypoint];
183 
184  keypoint.x = input[keypoint_index].x;
185  keypoint.y = input[keypoint_index].y;
186  keypoint.z = input[keypoint_index].z;
187  memcpy (reinterpret_cast<char*> (&keypoint) + out_fields_[scale_idx_].offset,
188  &scales[extrema_scales[i_keypoint]], sizeof (float));
189  output.push_back (keypoint);
190  }
191  }
192  else
193  {
194  // Add keypoints to output
195  for (const auto &keypoint_index : extrema_indices)
196  {
197  PointOutT keypoint;
198  keypoint.x = input[keypoint_index].x;
199  keypoint.y = input[keypoint_index].y;
200  keypoint.z = input[keypoint_index].z;
201 
202  output.push_back (keypoint);
203  }
204  }
205 }
206 
207 
208 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
209 template <typename PointInT, typename PointOutT>
211  const PointCloudIn &input, KdTree &tree, const std::vector<float> &scales,
212  Eigen::MatrixXf &diff_of_gauss)
213 {
214  diff_of_gauss.resize (input.size (), scales.size () - 1);
215 
216  // For efficiency, we will only filter over points within 3 standard deviations
217  const float max_radius = 3.0f * scales.back ();
218 
219  for (int i_point = 0; i_point < static_cast<int> (input.size ()); ++i_point)
220  {
221  pcl::Indices nn_indices;
222  std::vector<float> nn_dist;
223  tree.radiusSearch (i_point, max_radius, nn_indices, nn_dist); // *
224  // * note: at this stage of the algorithm, we must find all points within a radius defined by the maximum scale,
225  // regardless of the configurable search method specified by the user, so we directly employ tree.radiusSearch
226  // here instead of using searchForNeighbors.
227 
228  // For each scale, compute the Gaussian "filter response" at the current point
229  float filter_response = 0.0f;
230  for (std::size_t i_scale = 0; i_scale < scales.size (); ++i_scale)
231  {
232  float sigma_sqr = powf (scales[i_scale], 2.0f);
233 
234  float numerator = 0.0f;
235  float denominator = 0.0f;
236  for (std::size_t i_neighbor = 0; i_neighbor < nn_indices.size (); ++i_neighbor)
237  {
238  const float &value = getFieldValue_ (input[nn_indices[i_neighbor]]);
239  const float &dist_sqr = nn_dist[i_neighbor];
240  if (dist_sqr <= 9*sigma_sqr)
241  {
242  float w = std::exp (-0.5f * dist_sqr / sigma_sqr);
243  numerator += value * w;
244  denominator += w;
245  }
246  else break; // i.e. if dist > 3 standard deviations, then terminate early
247  }
248  float previous_filter_response = filter_response;
249  filter_response = numerator / denominator;
250 
251  // Compute the difference between adjacent scales
252  if (i_scale > 0)
253  diff_of_gauss (i_point, i_scale - 1) = filter_response - previous_filter_response;
254  }
255  }
256 }
257 
258 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
259 template <typename PointInT, typename PointOutT> void
261  const PointCloudIn &input, KdTree &tree, const Eigen::MatrixXf &diff_of_gauss,
262  pcl::Indices &extrema_indices, std::vector<int> &extrema_scales)
263 {
264  constexpr int k = 25;
265  pcl::Indices nn_indices (k);
266  std::vector<float> nn_dist (k);
267 
268  const int nr_scales = static_cast<int> (diff_of_gauss.cols ());
269  std::vector<float> min_val (nr_scales), max_val (nr_scales);
270 
271  for (int i_point = 0; i_point < static_cast<int> (input.size ()); ++i_point)
272  {
273  // Define the local neighborhood around the current point
274  const std::size_t nr_nn = tree.nearestKSearch (i_point, k, nn_indices, nn_dist); //*
275  // * note: the neighborhood for finding local extrema is best defined as a small fixed-k neighborhood, regardless of
276  // the configurable search method specified by the user, so we directly employ tree.nearestKSearch here instead
277  // of using searchForNeighbors
278 
279  // At each scale, find the extreme values of the DoG within the current neighborhood
280  for (int i_scale = 0; i_scale < nr_scales; ++i_scale)
281  {
282  min_val[i_scale] = std::numeric_limits<float>::max ();
283  max_val[i_scale] = -std::numeric_limits<float>::max ();
284 
285  for (std::size_t i_neighbor = 0; i_neighbor < nr_nn; ++i_neighbor)
286  {
287  const float &d = diff_of_gauss (nn_indices[i_neighbor], i_scale);
288 
289  min_val[i_scale] = (std::min) (min_val[i_scale], d);
290  max_val[i_scale] = (std::max) (max_val[i_scale], d);
291  }
292  }
293 
294  // If the current point is an extreme value with high enough contrast, add it as a keypoint
295  for (int i_scale = 1; i_scale < nr_scales - 1; ++i_scale)
296  {
297  const float &val = diff_of_gauss (i_point, i_scale);
298 
299  // Does the point have sufficient contrast?
300  if (std::abs (val) >= min_contrast_)
301  {
302  // Is it a local minimum?
303  if ((val == min_val[i_scale]) &&
304  (val < min_val[i_scale - 1]) &&
305  (val < min_val[i_scale + 1]))
306  {
307  extrema_indices.push_back (i_point);
308  extrema_scales.push_back (i_scale);
309  }
310  // Is it a local maximum?
311  else if ((val == max_val[i_scale]) &&
312  (val > max_val[i_scale - 1]) &&
313  (val > max_val[i_scale + 1]))
314  {
315  extrema_indices.push_back (i_point);
316  extrema_scales.push_back (i_scale);
317  }
318  }
319  }
320  }
321 }
322 
323 #define PCL_INSTANTIATE_SIFTKeypoint(T,U) template class PCL_EXPORTS pcl::SIFTKeypoint<T,U>;
324 
325 #endif // #ifndef PCL_SIFT_KEYPOINT_IMPL_H_
326 
void filter(PointCloud &output)
Calls the filtering method and returns the filtered dataset in output.
Definition: filter.h:121
KdTree represents the base spatial locator class for kd-tree implementations.
Definition: kdtree.h:56
virtual void setInputCloud(const PointCloudConstPtr &cloud)
Provide a pointer to the input dataset.
Definition: pcl_base.hpp:65
std::size_t size() const
Definition: point_cloud.h:443
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:413
SIFTKeypoint detects the Scale Invariant Feature Transform keypoints for a given point cloud dataset ...
Definition: sift_keypoint.h:94
bool initCompute() override
void setMinimumContrast(float min_contrast)
Provide a threshold to limit detection of keypoints without sufficient contrast.
void setScales(float min_scale, int nr_octaves, int nr_scales_per_octave)
Specify the range of scales over which to search for keypoints.
void detectKeypoints(PointCloudOut &output) override
Detect the SIFT keypoints for a set of points given in setInputCloud () using the spatial locator in ...
typename Keypoint< PointInT, PointOutT >::PointCloudOut PointCloudOut
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
search::KdTree is a wrapper class which inherits the pcl::KdTree class for performing search function...
Definition: kdtree.h:62
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:133