Point Cloud Library (PCL)  1.9.1-dev
feature.h
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  * Copyright (c) 2012-, Open Perception, Inc.
7  *
8  * All rights reserved.
9  *
10  * Redistribution and use in source and binary forms, with or without
11  * modification, are permitted provided that the following conditions
12  * are met:
13  *
14  * * Redistributions of source code must retain the above copyright
15  * notice, this list of conditions and the following disclaimer.
16  * * Redistributions in binary form must reproduce the above
17  * copyright notice, this list of conditions and the following
18  * disclaimer in the documentation and/or other materials provided
19  * with the distribution.
20  * * Neither the name of the copyright holder(s) nor the names of its
21  * contributors may be used to endorse or promote products derived
22  * from this software without specific prior written permission.
23  *
24  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
25  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
26  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
27  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
28  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
29  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
30  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
32  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
33  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
34  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35  * POSSIBILITY OF SUCH DAMAGE.
36  *
37  * $Id$
38  *
39  */
40 
41 #pragma once
42 
43 #if defined __GNUC__
44 # pragma GCC system_header
45 #endif
46 
47 #include <boost/function.hpp>
48 #include <boost/bind.hpp>
49 // PCL includes
50 #include <pcl/pcl_base.h>
51 #include <pcl/search/search.h>
52 
53 namespace pcl
54 {
55  /** \brief Solve the eigenvalues and eigenvectors of a given 3x3 covariance matrix, and estimate the least-squares
56  * plane normal and surface curvature.
57  * \param covariance_matrix the 3x3 covariance matrix
58  * \param point a point lying on the least-squares plane (SSE aligned)
59  * \param plane_parameters the resultant plane parameters as: a, b, c, d (ax + by + cz + d = 0)
60  * \param curvature the estimated surface curvature as a measure of
61  * \f[
62  * \lambda_0 / (\lambda_0 + \lambda_1 + \lambda_2)
63  * \f]
64  * \ingroup features
65  */
66  inline void
67  solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix,
68  const Eigen::Vector4f &point,
69  Eigen::Vector4f &plane_parameters, float &curvature);
70 
71  /** \brief Solve the eigenvalues and eigenvectors of a given 3x3 covariance matrix, and estimate the least-squares
72  * plane normal and surface curvature.
73  * \param covariance_matrix the 3x3 covariance matrix
74  * \param nx the resultant X component of the plane normal
75  * \param ny the resultant Y component of the plane normal
76  * \param nz the resultant Z component of the plane normal
77  * \param curvature the estimated surface curvature as a measure of
78  * \f[
79  * \lambda_0 / (\lambda_0 + \lambda_1 + \lambda_2)
80  * \f]
81  * \ingroup features
82  */
83  inline void
84  solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix,
85  float &nx, float &ny, float &nz, float &curvature);
86 
87  ////////////////////////////////////////////////////////////////////////////////////////////
88  ////////////////////////////////////////////////////////////////////////////////////////////
89  ////////////////////////////////////////////////////////////////////////////////////////////
90  /** \brief Feature represents the base feature class. Some generic 3D operations that
91  * are applicable to all features are defined here as static methods.
92  *
93  * \attention
94  * The convention for a feature descriptor is:
95  * - if the nearest neighbors for the query point at which the descriptor is to be computed cannot be
96  * determined, the descriptor values will be set to NaN (not a number)
97  * - it is impossible to estimate a feature descriptor for a point that doesn't have finite 3D coordinates.
98  * Therefore, any point that has NaN data on x, y, or z, will most likely have its descriptor set to NaN.
99  *
100  * \author Radu B. Rusu
101  * \ingroup features
102  */
103  template <typename PointInT, typename PointOutT>
104  class Feature : public PCLBase<PointInT>
105  {
106  public:
109 
111 
112  typedef boost::shared_ptr< Feature<PointInT, PointOutT> > Ptr;
113  typedef boost::shared_ptr< const Feature<PointInT, PointOutT> > ConstPtr;
114 
117 
121 
123 
124  typedef boost::function<int (size_t, double, std::vector<int> &, std::vector<float> &)> SearchMethod;
125  typedef boost::function<int (const PointCloudIn &cloud, size_t index, double, std::vector<int> &, std::vector<float> &)> SearchMethodSurface;
126 
127  public:
128  /** \brief Empty constructor. */
129  Feature () :
131  surface_(), tree_(),
133  fake_surface_(false)
134  {}
135 
136  /** \brief Empty destructor */
137  virtual ~Feature () {}
138 
139  /** \brief Provide a pointer to a dataset to add additional information
140  * to estimate the features for every point in the input dataset. This
141  * is optional, if this is not set, it will only use the data in the
142  * input cloud to estimate the features. This is useful when you only
143  * need to compute the features for a downsampled cloud.
144  * \param[in] cloud a pointer to a PointCloud message
145  */
146  inline void
147  setSearchSurface (const PointCloudInConstPtr &cloud)
148  {
149  surface_ = cloud;
150  fake_surface_ = false;
151  //use_surface_ = true;
152  }
153 
154  /** \brief Get a pointer to the surface point cloud dataset. */
155  inline PointCloudInConstPtr
157  {
158  return (surface_);
159  }
160 
161  /** \brief Provide a pointer to the search object.
162  * \param[in] tree a pointer to the spatial search object.
163  */
164  inline void
165  setSearchMethod (const KdTreePtr &tree) { tree_ = tree; }
166 
167  /** \brief Get a pointer to the search method used. */
168  inline KdTreePtr
170  {
171  return (tree_);
172  }
173 
174  /** \brief Get the internal search parameter. */
175  inline double
177  {
178  return (search_parameter_);
179  }
180 
181  /** \brief Set the number of k nearest neighbors to use for the feature estimation.
182  * \param[in] k the number of k-nearest neighbors
183  */
184  inline void
185  setKSearch (int k) { k_ = k; }
186 
187  /** \brief get the number of k nearest neighbors used for the feature estimation. */
188  inline int
189  getKSearch () const
190  {
191  return (k_);
192  }
193 
194  /** \brief Set the sphere radius that is to be used for determining the nearest neighbors used for the feature
195  * estimation.
196  * \param[in] radius the sphere radius used as the maximum distance to consider a point a neighbor
197  */
198  inline void
199  setRadiusSearch (double radius)
200  {
201  search_radius_ = radius;
202  }
203 
204  /** \brief Get the sphere radius used for determining the neighbors. */
205  inline double
207  {
208  return (search_radius_);
209  }
210 
211  /** \brief Base method for feature estimation for all points given in
212  * <setInputCloud (), setIndices ()> using the surface in setSearchSurface ()
213  * and the spatial locator in setSearchMethod ()
214  * \param[out] output the resultant point cloud model dataset containing the estimated features
215  */
216  void
217  compute (PointCloudOut &output);
218 
219  protected:
220  /** \brief The feature name. */
221  std::string feature_name_;
222 
223  /** \brief The search method template for points. */
225 
226  /** \brief An input point cloud describing the surface that is to be used
227  * for nearest neighbors estimation.
228  */
229  PointCloudInConstPtr surface_;
230 
231  /** \brief A pointer to the spatial search object. */
232  KdTreePtr tree_;
233 
234  /** \brief The actual search parameter (from either \a search_radius_ or \a k_). */
236 
237  /** \brief The nearest neighbors search radius for each point. */
239 
240  /** \brief The number of K nearest neighbors to use for each point. */
241  int k_;
242 
243  /** \brief Get a string representation of the name of this class. */
244  inline const std::string&
245  getClassName () const { return (feature_name_); }
246 
247  /** \brief This method should get called before starting the actual computation. */
248  virtual bool
249  initCompute ();
250 
251  /** \brief This method should get called after ending the actual computation. */
252  virtual bool
253  deinitCompute ();
254 
255  /** \brief If no surface is given, we use the input PointCloud as the surface. */
257 
258  /** \brief Search for k-nearest neighbors using the spatial locator from
259  * \a setSearchmethod, and the given surface from \a setSearchSurface.
260  * \param[in] index the index of the query point
261  * \param[in] parameter the search parameter (either k or radius)
262  * \param[out] indices the resultant vector of indices representing the k-nearest neighbors
263  * \param[out] distances the resultant vector of distances representing the distances from the query point to the
264  * k-nearest neighbors
265  *
266  * \return the number of neighbors found. If no neighbors are found or an error occurred, return 0.
267  */
268  inline int
269  searchForNeighbors (size_t index, double parameter,
270  std::vector<int> &indices, std::vector<float> &distances) const
271  {
272  return (search_method_surface_ (*input_, index, parameter, indices, distances));
273  }
274 
275  /** \brief Search for k-nearest neighbors using the spatial locator from
276  * \a setSearchmethod, and the given surface from \a setSearchSurface.
277  * \param[in] cloud the query point cloud
278  * \param[in] index the index of the query point in \a cloud
279  * \param[in] parameter the search parameter (either k or radius)
280  * \param[out] indices the resultant vector of indices representing the k-nearest neighbors
281  * \param[out] distances the resultant vector of distances representing the distances from the query point to the
282  * k-nearest neighbors
283  *
284  * \return the number of neighbors found. If no neighbors are found or an error occurred, return 0.
285  */
286  inline int
287  searchForNeighbors (const PointCloudIn &cloud, size_t index, double parameter,
288  std::vector<int> &indices, std::vector<float> &distances) const
289  {
290  return (search_method_surface_ (cloud, index, parameter, indices, distances));
291  }
292 
293  private:
294  /** \brief Abstract feature estimation method.
295  * \param[out] output the resultant features
296  */
297  virtual void
298  computeFeature (PointCloudOut &output) = 0;
299 
300  public:
301  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
302  };
303 
304 
305  ////////////////////////////////////////////////////////////////////////////////////////////
306  ////////////////////////////////////////////////////////////////////////////////////////////
307  ////////////////////////////////////////////////////////////////////////////////////////////
308  template <typename PointInT, typename PointNT, typename PointOutT>
309  class FeatureFromNormals : public Feature<PointInT, PointOutT>
310  {
312  typedef typename PointCloudIn::Ptr PointCloudInPtr;
315 
316  public:
319  typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;
320 
321  typedef boost::shared_ptr< FeatureFromNormals<PointInT, PointNT, PointOutT> > Ptr;
322  typedef boost::shared_ptr< const FeatureFromNormals<PointInT, PointNT, PointOutT> > ConstPtr;
323 
324  // Members derived from the base class
328 
329  /** \brief Empty constructor. */
330  FeatureFromNormals () : normals_ () {}
331 
332  /** \brief Empty destructor */
333  virtual ~FeatureFromNormals () {}
334 
335  /** \brief Provide a pointer to the input dataset that contains the point normals of
336  * the XYZ dataset.
337  * In case of search surface is set to be different from the input cloud,
338  * normals should correspond to the search surface, not the input cloud!
339  * \param[in] normals the const boost shared pointer to a PointCloud of normals.
340  * By convention, L2 norm of each normal should be 1.
341  */
342  inline void
343  setInputNormals (const PointCloudNConstPtr &normals) { normals_ = normals; }
344 
345  /** \brief Get a pointer to the normals of the input XYZ point cloud dataset. */
346  inline PointCloudNConstPtr
347  getInputNormals () const { return (normals_); }
348 
349  protected:
350  /** \brief A pointer to the input dataset that contains the point normals of the XYZ
351  * dataset.
352  */
353  PointCloudNConstPtr normals_;
354 
355  /** \brief This method should get called before starting the actual computation. */
356  virtual bool
357  initCompute ();
358 
359  public:
360  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
361  };
362 
363  ////////////////////////////////////////////////////////////////////////////////////////////
364  ////////////////////////////////////////////////////////////////////////////////////////////
365  ////////////////////////////////////////////////////////////////////////////////////////////
366  template <typename PointInT, typename PointLT, typename PointOutT>
367  class FeatureFromLabels : public Feature<PointInT, PointOutT>
368  {
370  typedef typename PointCloudIn::Ptr PointCloudInPtr;
372 
373  typedef typename pcl::PointCloud<PointLT> PointCloudL;
374  typedef typename PointCloudL::Ptr PointCloudNPtr;
375  typedef typename PointCloudL::ConstPtr PointCloudLConstPtr;
376 
378 
379  public:
380  typedef boost::shared_ptr< FeatureFromLabels<PointInT, PointLT, PointOutT> > Ptr;
381  typedef boost::shared_ptr< const FeatureFromLabels<PointInT, PointLT, PointOutT> > ConstPtr;
382 
383  // Members derived from the base class
388 
389  /** \brief Empty constructor. */
390  FeatureFromLabels () : labels_ ()
391  {
392  k_ = 1; // Search tree is not always used here.
393  }
394 
395  /** \brief Empty destructor */
396  virtual ~FeatureFromLabels () {}
397 
398  /** \brief Provide a pointer to the input dataset that contains the point labels of
399  * the XYZ dataset.
400  * In case of search surface is set to be different from the input cloud,
401  * labels should correspond to the search surface, not the input cloud!
402  * \param[in] labels the const boost shared pointer to a PointCloud of labels.
403  */
404  inline void
405  setInputLabels (const PointCloudLConstPtr &labels)
406  {
407  labels_ = labels;
408  }
409 
410  /** \brief Get a pointer to the labels of the input XYZ point cloud dataset. */
411  inline PointCloudLConstPtr
412  getInputLabels () const
413  {
414  return (labels_);
415  }
416 
417  protected:
418  /** \brief A pointer to the input dataset that contains the point labels of the XYZ
419  * dataset.
420  */
421  PointCloudLConstPtr labels_;
422 
423  /** \brief This method should get called before starting the actual computation. */
424  virtual bool
425  initCompute ();
426 
427  public:
428  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
429  };
430 
431  ////////////////////////////////////////////////////////////////////////////////////////////
432  ////////////////////////////////////////////////////////////////////////////////////////////
433  ////////////////////////////////////////////////////////////////////////////////////////////
434  /** \brief FeatureWithLocalReferenceFrames provides a public interface for descriptor
435  * extractor classes which need a local reference frame at each input keypoint.
436  *
437  * \attention
438  * This interface is for backward compatibility with existing code and in the future it could be
439  * merged with pcl::Feature. Subclasses should call the protected method initLocalReferenceFrames ()
440  * to correctly initialize the frames_ member.
441  *
442  * \author Nicola Fioraio
443  * \ingroup features
444  */
445  template <typename PointInT, typename PointRFT>
447  {
448  public:
452 
453  /** \brief Empty constructor. */
454  FeatureWithLocalReferenceFrames () : frames_ (), frames_never_defined_ (true) {}
455 
456  /** \brief Empty destructor. */
458 
459  /** \brief Provide a pointer to the input dataset that contains the local
460  * reference frames of the XYZ dataset.
461  * In case of search surface is set to be different from the input cloud,
462  * local reference frames should correspond to the input cloud, not the search surface!
463  * \param[in] frames the const boost shared pointer to a PointCloud of reference frames.
464  */
465  inline void
466  setInputReferenceFrames (const PointCloudLRFConstPtr &frames)
467  {
468  frames_ = frames;
469  frames_never_defined_ = false;
470  }
471 
472  /** \brief Get a pointer to the local reference frames. */
473  inline PointCloudLRFConstPtr
475  {
476  return (frames_);
477  }
478 
479  protected:
480  /** \brief A boost shared pointer to the local reference frames. */
481  PointCloudLRFConstPtr frames_;
482  /** \brief The user has never set the frames. */
484 
485  /** \brief Check if frames_ has been correctly initialized and compute it if needed.
486  * \param input the subclass' input cloud dataset.
487  * \param lrf_estimation a pointer to a local reference frame estimation class to be used as default.
488  * \return true if frames_ has been correctly initialized.
489  */
491  virtual bool
492  initLocalReferenceFrames (const size_t& indices_size,
493  const LRFEstimationPtr& lrf_estimation = LRFEstimationPtr());
494  };
495 }
496 
497 #include <pcl/features/impl/feature.hpp>
void setSearchSurface(const PointCloudInConstPtr &cloud)
Provide a pointer to a dataset to add additional information to estimate the features for every point...
Definition: feature.h:147
boost::function< int(const PointCloudIn &cloud, size_t index, double, std::vector< int > &, std::vector< float > &)> SearchMethodSurface
Definition: feature.h:125
PointCloudLRFConstPtr frames_
A boost shared pointer to the local reference frames.
Definition: feature.h:481
boost::shared_ptr< const FeatureFromNormals< PointInT, PointNT, PointOutT > > ConstPtr
Definition: feature.h:322
PointCloudLConstPtr getInputLabels() const
Get a pointer to the labels of the input XYZ point cloud dataset.
Definition: feature.h:412
FeatureFromNormals()
Empty constructor.
Definition: feature.h:330
boost::shared_ptr< const FeatureFromLabels< PointInT, PointLT, PointOutT > > ConstPtr
Definition: feature.h:381
PointCloudN::ConstPtr PointCloudNConstPtr
Definition: feature.h:319
virtual ~FeatureFromLabels()
Empty destructor.
Definition: feature.h:396
std::string feature_name_
The feature name.
Definition: feature.h:221
This file defines compatibility wrappers for low level I/O functions.
Definition: convolution.h:44
int k_
The number of K nearest neighbors to use for each point.
Definition: feature.h:241
PointCloudNConstPtr getInputNormals() const
Get a pointer to the normals of the input XYZ point cloud dataset.
Definition: feature.h:347
PointCloudN::Ptr PointCloudNPtr
Definition: feature.h:318
FeatureWithLocalReferenceFrames()
Empty constructor.
Definition: feature.h:454
void solvePlaneParameters(const Eigen::Matrix3f &covariance_matrix, const Eigen::Vector4f &point, Eigen::Vector4f &plane_parameters, float &curvature)
Solve the eigenvalues and eigenvectors of a given 3x3 covariance matrix, and estimate the least-squar...
Definition: feature.hpp:48
boost::shared_ptr< const Feature< PointInT, PointOutT > > ConstPtr
Definition: feature.h:113
virtual bool deinitCompute()
This method should get called after ending the actual computation.
Definition: feature.hpp:176
pcl::PointCloud< PointRFT > PointCloudLRF
Definition: feature.h:449
double getSearchParameter() const
Get the internal search parameter.
Definition: feature.h:176
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:199
const std::string & getClassName() const
Get a string representation of the name of this class.
Definition: feature.h:245
KdTreePtr tree_
A pointer to the spatial search object.
Definition: feature.h:232
pcl::PointCloud< PointOutT > PointCloudOut
Definition: feature.h:122
boost::shared_ptr< PointCloud< PointWithRange > > Ptr
Definition: point_cloud.h:427
PointCloudInConstPtr surface_
An input point cloud describing the surface that is to be used for nearest neighbors estimation...
Definition: feature.h:229
Feature< PointInT, PointRFT >::Ptr LRFEstimationPtr
Check if frames_ has been correctly initialized and compute it if needed.
Definition: feature.h:490
PointCloudIn::ConstPtr PointCloudInConstPtr
Definition: feature.h:120
pcl::search::Search< PointInT >::Ptr KdTreePtr
Definition: feature.h:116
boost::shared_ptr< pcl::search::Search< PointT > > Ptr
Definition: search.h:80
PointCloudInConstPtr getSearchSurface() const
Get a pointer to the surface point cloud dataset.
Definition: feature.h:156
PointCloudIn::Ptr PointCloudInPtr
Definition: feature.h:119
PCL base class.
Definition: pcl_base.h:68
pcl::PointCloud< PointInT > PointCloudIn
Definition: feature.h:118
bool fake_surface_
If no surface is given, we use the input PointCloud as the surface.
Definition: feature.h:256
boost::shared_ptr< const PointCloud< PointWithRange > > ConstPtr
Definition: point_cloud.h:428
void setInputReferenceFrames(const PointCloudLRFConstPtr &frames)
Provide a pointer to the input dataset that contains the local reference frames of the XYZ dataset...
Definition: feature.h:466
boost::shared_ptr< FeatureFromNormals< PointInT, PointNT, PointOutT > > Ptr
Definition: feature.h:321
PCLBase< PointInT > BaseClass
Definition: feature.h:110
boost::shared_ptr< FeatureFromLabels< PointInT, PointLT, PointOutT > > Ptr
Definition: feature.h:380
Feature()
Empty constructor.
Definition: feature.h:129
pcl::PointCloud< PointNT > PointCloudN
Definition: feature.h:317
double getRadiusSearch() const
Get the sphere radius used for determining the neighbors.
Definition: feature.h:206
bool frames_never_defined_
The user has never set the frames.
Definition: feature.h:483
virtual ~FeatureFromNormals()
Empty destructor.
Definition: feature.h:333
virtual bool initCompute()
This method should get called before starting the actual computation.
Definition: feature.hpp:93
void setSearchMethod(const KdTreePtr &tree)
Provide a pointer to the search object.
Definition: feature.h:165
pcl::search::Search< PointInT > KdTree
Definition: feature.h:115
KdTreePtr getSearchMethod() const
Get a pointer to the search method used.
Definition: feature.h:169
virtual ~Feature()
Empty destructor.
Definition: feature.h:137
int searchForNeighbors(const PointCloudIn &cloud, size_t index, double parameter, std::vector< int > &indices, std::vector< float > &distances) const
Search for k-nearest neighbors using the spatial locator from setSearchmethod, and the given surface ...
Definition: feature.h:287
PointCloudNConstPtr normals_
A pointer to the input dataset that contains the point normals of the XYZ dataset.
Definition: feature.h:353
PointCloudLConstPtr labels_
A pointer to the input dataset that contains the point labels of the XYZ dataset. ...
Definition: feature.h:421
void setInputLabels(const PointCloudLConstPtr &labels)
Provide a pointer to the input dataset that contains the point labels of the XYZ dataset.
Definition: feature.h:405
double search_parameter_
The actual search parameter (from either search_radius_ or k_).
Definition: feature.h:235
PointCloudConstPtr input_
The input point cloud dataset.
Definition: pcl_base.h:150
Feature represents the base feature class.
Definition: feature.h:104
FeatureWithLocalReferenceFrames provides a public interface for descriptor extractor classes which ne...
Definition: feature.h:446
boost::function< int(size_t, double, std::vector< int > &, std::vector< float > &)> SearchMethod
Definition: feature.h:124
void compute(PointCloudOut &output)
Base method for feature estimation for all points given in <setInputCloud (), setIndices ()> using th...
Definition: feature.hpp:189
boost::shared_ptr< Feature< PointInT, PointOutT > > Ptr
Definition: feature.h:112
int getKSearch() const
get the number of k nearest neighbors used for the feature estimation.
Definition: feature.h:189
PointCloudLRFConstPtr getInputReferenceFrames() const
Get a pointer to the local reference frames.
Definition: feature.h:474
PointCloudLRF::ConstPtr PointCloudLRFConstPtr
Definition: feature.h:451
void setKSearch(int k)
Set the number of k nearest neighbors to use for the feature estimation.
Definition: feature.h:185
void setInputNormals(const PointCloudNConstPtr &normals)
Provide a pointer to the input dataset that contains the point normals of the XYZ dataset...
Definition: feature.h:343
virtual ~FeatureWithLocalReferenceFrames()
Empty destructor.
Definition: feature.h:457
double search_radius_
The nearest neighbors search radius for each point.
Definition: feature.h:238
int searchForNeighbors(size_t index, double parameter, std::vector< int > &indices, std::vector< float > &distances) const
Search for k-nearest neighbors using the spatial locator from setSearchmethod, and the given surface ...
Definition: feature.h:269
SearchMethodSurface search_method_surface_
The search method template for points.
Definition: feature.h:224
PointCloudLRF::Ptr PointCloudLRFPtr
Definition: feature.h:450
FeatureFromLabels()
Empty constructor.
Definition: feature.h:390