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