Point Cloud Library (PCL)  1.14.0-dev
iss_3d.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2010, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  */
35 
36 #pragma once
37 
38 #include <pcl/keypoints/keypoint.h>
39 #include <pcl/octree/octree_search.h> // for OctreePointCloudSearch
40 
41 namespace pcl
42 {
43  /** \brief ISSKeypoint3D detects the Intrinsic Shape Signatures keypoints for a given
44  * point cloud. This class is based on a particular implementation made by Federico
45  * Tombari and Samuele Salti and it has been explicitly adapted to PCL.
46  *
47  * For more information about the original ISS detector, see:
48  *
49  *\par
50  * Yu Zhong, “Intrinsic shape signatures: A shape descriptor for 3D object recognition,”
51  * Computer Vision Workshops (ICCV Workshops), 2009 IEEE 12th International Conference on ,
52  * vol., no., pp.689-696, Sept. 27 2009-Oct. 4 2009
53  *
54  * Code example:
55  *
56  * \code
57  * pcl::PointCloud<pcl::PointXYZRGBA>::Ptr model (new pcl::PointCloud<pcl::PointXYZRGBA> ());
58  * pcl::PointCloud<pcl::PointXYZRGBA>::Ptr model_keypoints (new pcl::PointCloud<pcl::PointXYZRGBA> ());
59  * pcl::search::KdTree<pcl::PointXYZRGBA>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZRGBA> ());
60  *
61  * // Fill in the model cloud
62  *
63  * double model_resolution;
64  *
65  * // Compute model_resolution
66  *
67  * pcl::ISSKeypoint3D<pcl::PointXYZRGBA, pcl::PointXYZRGBA> iss_detector;
68  *
69  * iss_detector.setSearchMethod (tree);
70  * iss_detector.setSalientRadius (6 * model_resolution);
71  * iss_detector.setNonMaxRadius (4 * model_resolution);
72  * iss_detector.setThreshold21 (0.975);
73  * iss_detector.setThreshold32 (0.975);
74  * iss_detector.setMinNeighbors (5);
75  * iss_detector.setNumberOfThreads (4);
76  * iss_detector.setInputCloud (model);
77  * iss_detector.compute (*model_keypoints);
78  * \endcode
79  *
80  * \author Gioia Ballin
81  * \ingroup keypoints
82  */
83 
84  template <typename PointInT, typename PointOutT, typename NormalT = pcl::Normal>
85  class ISSKeypoint3D : public Keypoint<PointInT, PointOutT>
86  {
87  public:
88  using Ptr = shared_ptr<ISSKeypoint3D<PointInT, PointOutT, NormalT> >;
89  using ConstPtr = shared_ptr<const ISSKeypoint3D<PointInT, PointOutT, NormalT> >;
90 
93 
95  using PointCloudNPtr = typename PointCloudN::Ptr;
97 
100 
108 
109  /** \brief Constructor.
110  * \param[in] salient_radius the radius of the spherical neighborhood used to compute the scatter matrix.
111  */
112  ISSKeypoint3D (double salient_radius = 0.0001)
113  : salient_radius_ (salient_radius)
114  , normals_ (new pcl::PointCloud<NormalT>)
115  , angle_threshold_ (static_cast<float> (M_PI) / 2.0f)
116  {
117  name_ = "ISSKeypoint3D";
119  setNumberOfThreads(threads_); // Reset number of threads with the member's initialization value to apply input validation.
120  }
121 
122  /** \brief Destructor. */
123  ~ISSKeypoint3D () override
124  {
125  delete[] third_eigen_value_;
126  delete[] edge_points_;
127  }
128 
129  /** \brief Set the radius of the spherical neighborhood used to compute the scatter matrix.
130  * \param[in] salient_radius the radius of the spherical neighborhood
131  */
132  void
133  setSalientRadius (double salient_radius);
134 
135  /** \brief Set the radius for the application of the non maxima suppression algorithm.
136  * \param[in] non_max_radius the non maxima suppression radius
137  */
138  void
139  setNonMaxRadius (double non_max_radius);
140 
141  /** \brief Set the radius used for the estimation of the surface normals of the input cloud. If the radius is
142  * too large, the temporal performances of the detector may degrade significantly.
143  * \param[in] normal_radius the radius used to estimate surface normals
144  */
145  void
146  setNormalRadius (double normal_radius);
147 
148  /** \brief Set the radius used for the estimation of the boundary points. If the radius is too large,
149  * the temporal performances of the detector may degrade significantly.
150  * \param[in] border_radius the radius used to compute the boundary points
151  */
152  void
153  setBorderRadius (double border_radius);
154 
155  /** \brief Set the upper bound on the ratio between the second and the first eigenvalue.
156  * \param[in] gamma_21 the upper bound on the ratio between the second and the first eigenvalue
157  */
158  void
159  setThreshold21 (double gamma_21);
160 
161  /** \brief Set the upper bound on the ratio between the third and the second eigenvalue.
162  * \param[in] gamma_32 the upper bound on the ratio between the third and the second eigenvalue
163  */
164  void
165  setThreshold32 (double gamma_32);
166 
167  /** \brief Set the minimum number of neighbors that has to be found while applying the non maxima suppression algorithm.
168  * \param[in] min_neighbors the minimum number of neighbors required
169  */
170  void
171  setMinNeighbors (int min_neighbors);
172 
173  /** \brief Set the normals if pre-calculated normals are available.
174  * \param[in] normals the given cloud of normals
175  */
176  void
177  setNormals (const PointCloudNConstPtr &normals);
178 
179  /** \brief Set the decision boundary (angle threshold) that marks points as boundary or regular.
180  * (default \f$\pi / 2.0\f$)
181  * \param[in] angle the angle threshold
182  */
183  inline void
184  setAngleThreshold (float angle)
185  {
186  angle_threshold_ = angle;
187  }
188 
189  /** \brief Initialize the scheduler and set the number of threads to use.
190  * \param[in] nr_threads the number of hardware threads to use (0 sets the value back to automatic)
191  */
192  void
193  setNumberOfThreads (unsigned int nr_threads = 0);
194 
195  protected:
196 
197  /** \brief Compute the boundary points for the given input cloud.
198  * \param[in] input the input cloud
199  * \param[in] border_radius the radius used to compute the boundary points
200  * \param[in] angle_threshold the decision boundary that marks the points as boundary
201  * \return the vector of boolean values in which the information about the boundary points is stored
202  */
203  bool*
204  getBoundaryPoints (PointCloudIn &input, double border_radius, float angle_threshold);
205 
206  /** \brief Compute the scatter matrix for a point index.
207  * \param[in] current_index the index of the point
208  * \param[out] cov_m the point scatter matrix
209  */
210  void
211  getScatterMatrix (const int &current_index, Eigen::Matrix3d &cov_m);
212 
213  /** \brief Perform the initial checks before computing the keypoints.
214  * \return true if all the checks are passed, false otherwise
215  */
216  bool
217  initCompute () override;
218 
219  /** \brief Detect the keypoints by performing the EVD of the scatter matrix.
220  * \param[out] output the resultant cloud of keypoints
221  */
222  void
223  detectKeypoints (PointCloudOut &output) override;
224 
225 
226  /** \brief The radius of the spherical neighborhood used to compute the scatter matrix.*/
228 
229  /** \brief The non maxima suppression radius. */
230  double non_max_radius_{0.0};
231 
232  /** \brief The radius used to compute the normals of the input cloud. */
233  double normal_radius_{0.0};
234 
235  /** \brief The radius used to compute the boundary points of the input cloud. */
236  double border_radius_{0.0};
237 
238  /** \brief The upper bound on the ratio between the second and the first eigenvalue returned by the EVD. */
239  double gamma_21_{0.975};
240 
241  /** \brief The upper bound on the ratio between the third and the second eigenvalue returned by the EVD. */
242  double gamma_32_{0.975};
243 
244  /** \brief Store the third eigen value associated to each point in the input cloud. */
245  double *third_eigen_value_{nullptr};
246 
247  /** \brief Store the information about the boundary points of the input cloud. */
248  bool *edge_points_{nullptr};
249 
250  /** \brief Minimum number of neighbors that has to be found while applying the non maxima suppression algorithm. */
252 
253  /** \brief The cloud of normals related to the input surface. */
255 
256  /** \brief The decision boundary (angle threshold) that marks points as boundary or regular. (default \f$\pi / 2.0\f$) */
258 
259  /** \brief The number of threads that has to be used by the scheduler. */
260  unsigned int threads_{0};
261 
262  };
263 
264 }
265 
266 #include <pcl/keypoints/impl/iss_3d.hpp>
ISSKeypoint3D detects the Intrinsic Shape Signatures keypoints for a given point cloud.
Definition: iss_3d.h:86
typename OctreeSearchIn::Ptr OctreeSearchInPtr
Definition: iss_3d.h:99
double * third_eigen_value_
Store the third eigen value associated to each point in the input cloud.
Definition: iss_3d.h:245
typename PointCloudN::ConstPtr PointCloudNConstPtr
Definition: iss_3d.h:96
void setNumberOfThreads(unsigned int nr_threads=0)
Initialize the scheduler and set the number of threads to use.
Definition: iss_3d.hpp:106
typename Keypoint< PointInT, PointOutT >::PointCloudIn PointCloudIn
Definition: iss_3d.h:91
void setNormals(const PointCloudNConstPtr &normals)
Set the normals if pre-calculated normals are available.
Definition: iss_3d.hpp:99
shared_ptr< ISSKeypoint3D< PointInT, PointOutT, NormalT > > Ptr
Definition: iss_3d.h:88
double gamma_32_
The upper bound on the ratio between the third and the second eigenvalue returned by the EVD.
Definition: iss_3d.h:242
void setBorderRadius(double border_radius)
Set the radius used for the estimation of the boundary points.
Definition: iss_3d.hpp:71
void setSalientRadius(double salient_radius)
Set the radius of the spherical neighborhood used to compute the scatter matrix.
Definition: iss_3d.hpp:50
void getScatterMatrix(const int &current_index, Eigen::Matrix3d &cov_m)
Compute the scatter matrix for a point index.
Definition: iss_3d.hpp:165
double salient_radius_
The radius of the spherical neighborhood used to compute the scatter matrix.
Definition: iss_3d.h:227
bool * edge_points_
Store the information about the boundary points of the input cloud.
Definition: iss_3d.h:248
void setThreshold21(double gamma_21)
Set the upper bound on the ratio between the second and the first eigenvalue.
Definition: iss_3d.hpp:78
void setAngleThreshold(float angle)
Set the decision boundary (angle threshold) that marks points as boundary or regular.
Definition: iss_3d.h:184
void setMinNeighbors(int min_neighbors)
Set the minimum number of neighbors that has to be found while applying the non maxima suppression al...
Definition: iss_3d.hpp:92
double gamma_21_
The upper bound on the ratio between the second and the first eigenvalue returned by the EVD.
Definition: iss_3d.h:239
void setNormalRadius(double normal_radius)
Set the radius used for the estimation of the surface normals of the input cloud.
Definition: iss_3d.hpp:64
double non_max_radius_
The non maxima suppression radius.
Definition: iss_3d.h:230
void setThreshold32(double gamma_32)
Set the upper bound on the ratio between the third and the second eigenvalue.
Definition: iss_3d.hpp:85
PointCloudNConstPtr normals_
The cloud of normals related to the input surface.
Definition: iss_3d.h:254
unsigned int threads_
The number of threads that has to be used by the scheduler.
Definition: iss_3d.h:260
float angle_threshold_
The decision boundary (angle threshold) that marks points as boundary or regular.
Definition: iss_3d.h:257
bool initCompute() override
Perform the initial checks before computing the keypoints.
Definition: iss_3d.hpp:212
~ISSKeypoint3D() override
Destructor.
Definition: iss_3d.h:123
ISSKeypoint3D(double salient_radius=0.0001)
Constructor.
Definition: iss_3d.h:112
double normal_radius_
The radius used to compute the normals of the input cloud.
Definition: iss_3d.h:233
double border_radius_
The radius used to compute the boundary points of the input cloud.
Definition: iss_3d.h:236
typename PointCloudN::Ptr PointCloudNPtr
Definition: iss_3d.h:95
void setNonMaxRadius(double non_max_radius)
Set the radius for the application of the non maxima suppression algorithm.
Definition: iss_3d.hpp:57
int min_neighbors_
Minimum number of neighbors that has to be found while applying the non maxima suppression algorithm.
Definition: iss_3d.h:251
bool * getBoundaryPoints(PointCloudIn &input, double border_radius, float angle_threshold)
Compute the boundary points for the given input cloud.
Definition: iss_3d.hpp:120
shared_ptr< const ISSKeypoint3D< PointInT, PointOutT, NormalT > > ConstPtr
Definition: iss_3d.h:89
void detectKeypoints(PointCloudOut &output) override
Detect the keypoints by performing the EVD of the scatter matrix.
Definition: iss_3d.hpp:303
typename Keypoint< PointInT, PointOutT >::PointCloudOut PointCloudOut
Definition: iss_3d.h:92
Keypoint represents the base class for key points.
Definition: keypoint.h:49
std::string name_
The key point detection method's name.
Definition: keypoint.h:167
double search_radius_
The nearest neighbors search radius for each point.
Definition: keypoint.h:185
shared_ptr< PointCloud< NormalT > > Ptr
Definition: point_cloud.h:413
shared_ptr< const PointCloud< NormalT > > ConstPtr
Definition: point_cloud.h:414
Octree pointcloud search class
Definition: octree_search.h:58
shared_ptr< OctreePointCloudSearch< PointT, LeafContainerT, BranchContainerT > > Ptr
Definition: octree_search.h:70
#define M_PI
Definition: pcl_macros.h:201
A point structure representing normal coordinates and the surface curvature estimate.