Point Cloud Library (PCL)  1.11.0
implicit_shape_model.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, 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 <vector>
39 #include <fstream>
40 #include <limits>
41 #include <Eigen/src/Core/Matrix.h>
42 #include <pcl/memory.h>
43 #include <pcl/pcl_base.h>
44 #include <pcl/pcl_macros.h>
45 #include <pcl/point_types.h>
46 #include <pcl/point_representation.h>
47 #include <pcl/features/feature.h>
48 #include <pcl/features/spin_image.h>
49 #include <pcl/filters/voxel_grid.h>
50 #include <pcl/filters/extract_indices.h>
51 #include <pcl/search/search.h>
52 #include <pcl/kdtree/kdtree.h>
53 
54 namespace pcl
55 {
56  /** \brief This struct is used for storing peak. */
57  struct EIGEN_ALIGN16 ISMPeak
58  {
59  /** \brief Point were this peak is located. */
61 
62  /** \brief Density of this peak. */
63  double density;
64 
65  /** \brief Determines which class this peak belongs. */
66  int class_id;
67 
69  };
70 
71  namespace features
72  {
73  /** \brief This class is used for storing, analyzing and manipulating votes
74  * obtained from ISM algorithm. */
75  template <typename PointT>
77  {
78  public:
79 
80  using Ptr = shared_ptr<ISMVoteList<PointT> >;
81  using ConstPtr = shared_ptr<const ISMVoteList<PointT>>;
82 
83  /** \brief Empty constructor with member variables initialization. */
84  ISMVoteList ();
85 
86  /** \brief virtual descriptor. */
87  virtual
88  ~ISMVoteList ();
89 
90  /** \brief This method simply adds another vote to the list.
91  * \param[in] in_vote vote to add
92  * \param[in] vote_origin origin of the added vote
93  * \param[in] in_class class for which this vote is cast
94  */
95  void
96  addVote (pcl::InterestPoint& in_vote, const PointT &vote_origin, int in_class);
97 
98  /** \brief Returns the colored cloud that consists of votes for center (blue points) and
99  * initial point cloud (if it was passed).
100  * \param[in] cloud cloud that needs to be merged with votes for visualizing. */
102  getColoredCloud (typename pcl::PointCloud<PointT>::Ptr cloud = 0);
103 
104  /** \brief This method finds the strongest peaks (points were density has most higher values).
105  * It is based on the non maxima supression principles.
106  * \param[out] out_peaks it will contain the strongest peaks
107  * \param[in] in_class_id class of interest for which peaks are evaluated
108  * \param[in] in_non_maxima_radius non maxima supression radius. The shapes radius is recommended for this value.
109  * \param in_sigma
110  */
111  void
112  findStrongestPeaks (std::vector<ISMPeak, Eigen::aligned_allocator<ISMPeak> > &out_peaks, int in_class_id, double in_non_maxima_radius, double in_sigma);
113 
114  /** \brief Returns the density at the specified point.
115  * \param[in] point point of interest
116  * \param[in] sigma_dist
117  */
118  double
119  getDensityAtPoint (const PointT &point, double sigma_dist);
120 
121  /** \brief This method simply returns the number of votes. */
122  unsigned int
123  getNumberOfVotes ();
124 
125  protected:
126 
127  /** \brief this method is simply setting up the search tree. */
128  void
129  validateTree ();
130 
131  Eigen::Vector3f
132  shiftMean (const Eigen::Vector3f& snapPt, const double in_dSigmaDist);
133 
134  protected:
135 
136  /** \brief Stores all votes. */
138 
139  /** \brief Signalizes if the tree is valid. */
141 
142  /** \brief Stores the origins of the votes. */
144 
145  /** \brief Stores classes for which every single vote was cast. */
146  std::vector<int> votes_class_;
147 
148  /** \brief Stores the search tree. */
150 
151  /** \brief Stores neighbours indices. */
152  std::vector<int> k_ind_;
153 
154  /** \brief Stores square distances to the corresponding neighbours. */
155  std::vector<float> k_sqr_dist_;
156  };
157 
158  /** \brief The assignment of this structure is to store the statistical/learned weights and other information
159  * of the trained Implict Shape Model algorithm.
160  */
162  {
163  using Ptr = shared_ptr<ISMModel>;
164  using ConstPtr = shared_ptr<const ISMModel>;
165 
166  /** \brief Simple constructor that initializes the structure. */
167  ISMModel ();
168 
169  /** \brief Copy constructor for deep copy. */
170  ISMModel (ISMModel const & copy);
171 
172  /** Destructor that frees memory. */
173  virtual
174  ~ISMModel ();
175 
176  /** \brief This method simply saves the trained model for later usage.
177  * \param[in] file_name path to file for saving model
178  */
179  bool
180  saveModelToFile (std::string& file_name);
181 
182  /** \brief This method loads the trained model from file.
183  * \param[in] file_name path to file which stores trained model
184  */
185  bool
186  loadModelFromfile (std::string& file_name);
187 
188  /** \brief this method resets all variables and frees memory. */
189  void
190  reset ();
191 
192  /** Operator overloading for deep copy. */
193  ISMModel & operator = (const ISMModel& other);
194 
195  /** \brief Stores statistical weights. */
196  std::vector<std::vector<float> > statistical_weights_;
197 
198  /** \brief Stores learned weights. */
199  std::vector<float> learned_weights_;
200 
201  /** \brief Stores the class label for every direction. */
202  std::vector<unsigned int> classes_;
203 
204  /** \brief Stores the sigma value for each class. This values were used to compute the learned weights. */
205  std::vector<float> sigmas_;
206 
207  /** \brief Stores the directions to objects center for each visual word. */
208  Eigen::MatrixXf directions_to_center_;
209 
210  /** \brief Stores the centers of the clusters that were obtained during the visual words clusterization. */
211  Eigen::MatrixXf clusters_centers_;
212 
213  /** \brief This is an array of clusters. Each cluster stores the indices of the visual words that it contains. */
214  std::vector<std::vector<unsigned int> > clusters_;
215 
216  /** \brief Stores the number of classes. */
217  unsigned int number_of_classes_;
218 
219  /** \brief Stores the number of visual words. */
221 
222  /** \brief Stores the number of clusters. */
223  unsigned int number_of_clusters_;
224 
225  /** \brief Stores descriptors dimension. */
227 
229  };
230  }
231 
232  namespace ism
233  {
234  /** \brief This class implements Implicit Shape Model algorithm described in
235  * "Hough Transforms and 3D SURF for robust three dimensional classication"
236  * by Jan Knopp1, Mukta Prasad, Geert Willems1, Radu Timofte, and Luc Van Gool.
237  * It has two main member functions. One for training, using the data for which we know
238  * which class it belongs to. And second for investigating a cloud for the presence
239  * of the class of interest.
240  * Implementation of the ISM algorithm described in "Hough Transforms and 3D SURF for robust three dimensional classication"
241  * by Jan Knopp, Mukta Prasad, Geert Willems, Radu Timofte, and Luc Van Gool
242  *
243  * Authors: Roman Shapovalov, Alexander Velizhev, Sergey Ushakov
244  */
245  template <int FeatureSize, typename PointT, typename NormalT = pcl::Normal>
247  {
248  public:
249 
252  using FeaturePtr = typename Feature::Ptr;
253 
254  protected:
255 
256  /** \brief This structure stores the information about the keypoint. */
258  {
259  /** \brief Location info constructor.
260  * \param[in] model_num number of training model.
261  * \param[in] dir_to_center expected direction to center
262  * \param[in] origin initial point
263  * \param[in] normal normal of the initial point
264  */
265  LocationInfo (unsigned int model_num, const PointT& dir_to_center, const PointT& origin, const NormalT& normal) :
266  model_num_ (model_num),
267  dir_to_center_ (dir_to_center),
268  point_ (origin),
269  normal_ (normal) {};
270 
271  /** \brief Tells from which training model this keypoint was extracted. */
272  unsigned int model_num_;
273 
274  /** \brief Expected direction to center for this keypoint. */
276 
277  /** \brief Stores the initial point. */
279 
280  /** \brief Stores the normal of the initial point. */
282  };
283 
284  /** \brief This structure is used for determining the end of the
285  * k-means clustering process. */
287  {
288  enum
289  {
290  COUNT = 1,
291  EPS = 2
292  };
293 
294  /** \brief Termination criteria constructor.
295  * \param[in] type defines the condition of termination(max iter., desired accuracy)
296  * \param[in] max_count defines the max number of iterations
297  * \param[in] epsilon defines the desired accuracy
298  */
299  TermCriteria(int type, int max_count, float epsilon) :
300  type_ (type),
301  max_count_ (max_count),
302  epsilon_ (epsilon) {};
303 
304  /** \brief Flag that determines when the k-means clustering must be stopped.
305  * If type_ equals COUNT then it must be stopped when the max number of iterations will be
306  * reached. If type_ eaquals EPS then it must be stopped when the desired accuracy will be reached.
307  * These flags can be used together, in that case the clustering will be finished when one of these
308  * conditions will be reached.
309  */
310  int type_;
311 
312  /** \brief Defines maximum number of iterations for k-means clustering. */
314 
315  /** \brief Defines the accuracy for k-means clustering. */
316  float epsilon_;
317  };
318 
319  /** \brief Structure for storing the visual word. */
321  {
322  /** \brief Empty constructor with member variables initialization. */
324  class_ (-1),
325  learned_weight_ (0.0f),
326  dir_to_center_ (0.0f, 0.0f, 0.0f) {};
327 
328  /** \brief Which class this vote belongs. */
329  int class_;
330 
331  /** \brief Weight of the vote. */
333 
334  /** \brief Expected direction to center. */
336  };
337 
338  public:
339 
340  /** \brief Simple constructor that initializes everything. */
342 
343  /** \brief Simple destructor. */
344  virtual
346 
347  /** \brief This method simply returns the clouds that were set as the training clouds. */
348  std::vector<typename pcl::PointCloud<PointT>::Ptr>
349  getTrainingClouds ();
350 
351  /** \brief Allows to set clouds for training the ISM model.
352  * \param[in] training_clouds array of point clouds for training
353  */
354  void
355  setTrainingClouds (const std::vector< typename pcl::PointCloud<PointT>::Ptr >& training_clouds);
356 
357  /** \brief Returns the array of classes that indicates which class the corresponding training cloud belongs. */
358  std::vector<unsigned int>
359  getTrainingClasses ();
360 
361  /** \brief Allows to set the class labels for the corresponding training clouds.
362  * \param[in] training_classes array of class labels
363  */
364  void
365  setTrainingClasses (const std::vector<unsigned int>& training_classes);
366 
367  /** \brief This method returns the corresponding cloud of normals for every training point cloud. */
368  std::vector<typename pcl::PointCloud<NormalT>::Ptr>
369  getTrainingNormals ();
370 
371  /** \brief Allows to set normals for the training clouds that were passed through setTrainingClouds method.
372  * \param[in] training_normals array of clouds, each cloud is the cloud of normals
373  */
374  void
375  setTrainingNormals (const std::vector< typename pcl::PointCloud<NormalT>::Ptr >& training_normals);
376 
377  /** \brief Returns the sampling size used for cloud simplification. */
378  float
379  getSamplingSize ();
380 
381  /** \brief Changes the sampling size used for cloud simplification.
382  * \param[in] sampling_size desired size of grid bin
383  */
384  void
385  setSamplingSize (float sampling_size);
386 
387  /** \brief Returns the current feature estimator used for extraction of the descriptors. */
388  FeaturePtr
389  getFeatureEstimator ();
390 
391  /** \brief Changes the feature estimator.
392  * \param[in] feature feature estimator that will be used to extract the descriptors.
393  * Note that it must be fully initialized and configured.
394  */
395  void
396  setFeatureEstimator (FeaturePtr feature);
397 
398  /** \brief Returns the number of clusters used for descriptor clustering. */
399  unsigned int
400  getNumberOfClusters ();
401 
402  /** \brief Changes the number of clusters.
403  * \param num_of_clusters desired number of clusters
404  */
405  void
406  setNumberOfClusters (unsigned int num_of_clusters);
407 
408  /** \brief Returns the array of sigma values. */
409  std::vector<float>
410  getSigmaDists ();
411 
412  /** \brief This method allows to set the value of sigma used for calculating the learned weights for every single class.
413  * \param[in] training_sigmas new sigmas for every class. If you want these values to be computed automatically,
414  * just pass the empty array. The automatic regime calculates the maximum distance between the objects points and takes 10% of
415  * this value as recommended in the article. If there are several objects of the same class,
416  * then it computes the average maximum distance and takes 10%. Note that each class has its own sigma value.
417  */
418  void
419  setSigmaDists (const std::vector<float>& training_sigmas);
420 
421  /** \brief Returns the state of Nvot coeff from [Knopp et al., 2010, (4)],
422  * if set to false then coeff is taken as 1.0. It is just a kind of heuristic.
423  * The default behavior is as in the article. So you can ignore this if you want.
424  */
425  bool
426  getNVotState ();
427 
428  /** \brief Changes the state of the Nvot coeff from [Knopp et al., 2010, (4)].
429  * \param[in] state desired state, if false then Nvot is taken as 1.0
430  */
431  void
432  setNVotState (bool state);
433 
434  /** \brief This method performs training and forms a visual vocabulary. It returns a trained model that
435  * can be saved to file for later usage.
436  * \param[out] trained_model trained model
437  */
438  bool
439  trainISM (ISMModelPtr& trained_model);
440 
441  /** \brief This function is searching for the class of interest in a given cloud
442  * and returns the list of votes.
443  * \param[in] model trained model which will be used for searching the objects
444  * \param[in] in_cloud input cloud that need to be investigated
445  * \param[in] in_normals cloud of normals corresponding to the input cloud
446  * \param[in] in_class_of_interest class which we are looking for
447  */
449  findObjects (ISMModelPtr model, typename pcl::PointCloud<PointT>::Ptr in_cloud, typename pcl::PointCloud<Normal>::Ptr in_normals, int in_class_of_interest);
450 
451  protected:
452 
453  /** \brief Extracts the descriptors from the input clouds.
454  * \param[out] histograms it will store the descriptors for each key point
455  * \param[out] locations it will contain the comprehensive information (such as direction, initial keypoint)
456  * for the corresponding descriptors
457  */
458  bool
459  extractDescriptors (std::vector<pcl::Histogram<FeatureSize> >& histograms,
460  std::vector<LocationInfo, Eigen::aligned_allocator<LocationInfo> >& locations);
461 
462  /** \brief This method performs descriptor clustering.
463  * \param[in] histograms descriptors to cluster
464  * \param[out] labels it contains labels for each descriptor
465  * \param[out] clusters_centers stores the centers of clusters
466  */
467  bool
468  clusterDescriptors (std::vector< pcl::Histogram<FeatureSize> >& histograms, Eigen::MatrixXi& labels, Eigen::MatrixXf& clusters_centers);
469 
470  /** \brief This method calculates the value of sigma used for calculating the learned weights for every single class.
471  * \param[out] sigmas computed sigmas.
472  */
473  void
474  calculateSigmas (std::vector<float>& sigmas);
475 
476  /** \brief This function forms a visual vocabulary and evaluates weights
477  * described in [Knopp et al., 2010, (5)].
478  * \param[in] locations array containing description of each keypoint: its position, which cloud belongs
479  * and expected direction to center
480  * \param[in] labels labels that were obtained during k-means clustering
481  * \param[in] sigmas array of sigmas for each class
482  * \param[in] clusters clusters that were obtained during k-means clustering
483  * \param[out] statistical_weights stores the computed statistical weights
484  * \param[out] learned_weights stores the computed learned weights
485  */
486  void
487  calculateWeights (const std::vector< LocationInfo, Eigen::aligned_allocator<LocationInfo> >& locations,
488  const Eigen::MatrixXi &labels,
489  std::vector<float>& sigmas,
490  std::vector<std::vector<unsigned int> >& clusters,
491  std::vector<std::vector<float> >& statistical_weights,
492  std::vector<float>& learned_weights);
493 
494  /** \brief Simplifies the cloud using voxel grid principles.
495  * \param[in] in_point_cloud cloud that need to be simplified
496  * \param[in] in_normal_cloud normals of the cloud that need to be simplified
497  * \param[out] out_sampled_point_cloud simplified cloud
498  * \param[out] out_sampled_normal_cloud and the corresponding normals
499  */
500  void
501  simplifyCloud (typename pcl::PointCloud<PointT>::ConstPtr in_point_cloud,
502  typename pcl::PointCloud<NormalT>::ConstPtr in_normal_cloud,
503  typename pcl::PointCloud<PointT>::Ptr out_sampled_point_cloud,
504  typename pcl::PointCloud<NormalT>::Ptr out_sampled_normal_cloud);
505 
506  /** \brief This method simply shifts the clouds points relative to the passed point.
507  * \param[in] in_cloud cloud to shift
508  * \param[in] shift_point point relative to which the cloud will be shifted
509  */
510  void
511  shiftCloud (typename pcl::PointCloud<PointT>::Ptr in_cloud, Eigen::Vector3f shift_point);
512 
513  /** \brief This method simply computes the rotation matrix, so that the given normal
514  * would match the Y axis after the transformation. This is done because the algorithm needs to be invariant
515  * to the affine transformations.
516  * \param[in] in_normal normal for which the rotation matrix need to be computed
517  */
518  Eigen::Matrix3f
519  alignYCoordWithNormal (const NormalT& in_normal);
520 
521  /** \brief This method applies transform set in in_transform to vector io_vector.
522  * \param[in] io_vec vector that need to be transformed
523  * \param[in] in_transform matrix that contains the transformation
524  */
525  void
526  applyTransform (Eigen::Vector3f& io_vec, const Eigen::Matrix3f& in_transform);
527 
528  /** \brief This method estimates features for the given point cloud.
529  * \param[in] sampled_point_cloud sampled point cloud for which the features must be computed
530  * \param[in] normal_cloud normals for the original point cloud
531  * \param[out] feature_cloud it will store the computed histograms (features) for the given cloud
532  */
533  void
534  estimateFeatures (typename pcl::PointCloud<PointT>::Ptr sampled_point_cloud,
535  typename pcl::PointCloud<NormalT>::Ptr normal_cloud,
536  typename pcl::PointCloud<pcl::Histogram<FeatureSize> >::Ptr feature_cloud);
537 
538  /** \brief Performs K-means clustering.
539  * \param[in] points_to_cluster points to cluster
540  * \param[in] number_of_clusters desired number of clusters
541  * \param[out] io_labels output parameter, which stores the label for each point
542  * \param[in] criteria defines when the computational process need to be finished. For example if the
543  * desired accuracy is achieved or the iteration number exceeds given value
544  * \param[in] attempts number of attempts to compute clustering
545  * \param[in] flags if set to USE_INITIAL_LABELS then initial approximation of labels is taken from io_labels
546  * \param[out] cluster_centers it will store the cluster centers
547  */
548  double
549  computeKMeansClustering (const Eigen::MatrixXf& points_to_cluster,
550  int number_of_clusters,
551  Eigen::MatrixXi& io_labels,
552  TermCriteria criteria,
553  int attempts,
554  int flags,
555  Eigen::MatrixXf& cluster_centers);
556 
557  /** \brief Generates centers for clusters as described in
558  * Arthur, David and Sergei Vassilvitski (2007) k-means++: The Advantages of Careful Seeding.
559  * \param[in] data points to cluster
560  * \param[out] out_centers it will contain generated centers
561  * \param[in] number_of_clusters defines the number of desired cluster centers
562  * \param[in] trials number of trials to generate a center
563  */
564  void
565  generateCentersPP (const Eigen::MatrixXf& data,
566  Eigen::MatrixXf& out_centers,
567  int number_of_clusters,
568  int trials);
569 
570  /** \brief Generates random center for cluster.
571  * \param[in] boxes contains min and max values for each dimension
572  * \param[out] center it will the contain generated center
573  */
574  void
575  generateRandomCenter (const std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> >& boxes, Eigen::VectorXf& center);
576 
577  /** \brief Computes the square distance between two vectors.
578  * \param[in] vec_1 first vector
579  * \param[in] vec_2 second vector
580  */
581  float
582  computeDistance (Eigen::VectorXf& vec_1, Eigen::VectorXf& vec_2);
583 
584  /** \brief Forbids the assignment operator. */
586  operator= (const ImplicitShapeModelEstimation&);
587 
588  protected:
589 
590  /** \brief Stores the clouds used for training. */
591  std::vector<typename pcl::PointCloud<PointT>::Ptr> training_clouds_;
592 
593  /** \brief Stores the class number for each cloud from training_clouds_. */
594  std::vector<unsigned int> training_classes_;
595 
596  /** \brief Stores the normals for each training cloud. */
597  std::vector<typename pcl::PointCloud<NormalT>::Ptr> training_normals_;
598 
599  /** \brief This array stores the sigma values for each training class. If this array has a size equals 0, then
600  * sigma values will be calculated automatically.
601  */
602  std::vector<float> training_sigmas_;
603 
604  /** \brief This value is used for the simplification. It sets the size of grid bin. */
606 
607  /** \brief Stores the feature estimator. */
609 
610  /** \brief Number of clusters, is used for clustering descriptors during the training. */
611  unsigned int number_of_clusters_;
612 
613  /** \brief If set to false then Nvot coeff from [Knopp et al., 2010, (4)] is equal 1.0. */
614  bool n_vot_ON_;
615 
616  /** \brief This const value is used for indicating that for k-means clustering centers must
617  * be generated as described in
618  * Arthur, David and Sergei Vassilvitski (2007) k-means++: The Advantages of Careful Seeding. */
619  static const int PP_CENTERS = 2;
620 
621  /** \brief This const value is used for indicating that input labels must be taken as the
622  * initial approximation for k-means clustering. */
623  static const int USE_INITIAL_LABELS = 1;
624  };
625  }
626 }
627 
629  (float, x, x)
630  (float, y, y)
631  (float, z, z)
632  (float, density, ism_density)
633  (float, class_id, ism_class_id)
634 )
pcl_macros.h
Defines all the PCL and non-PCL macros used.
pcl
Definition: convolution.h:46
pcl::Feature::Ptr
shared_ptr< Feature< PointInT, PointOutT > > Ptr
Definition: feature.h:114
pcl::features::ISMModel::learned_weights_
std::vector< float > learned_weights_
Stores learned weights.
Definition: implicit_shape_model.h:199
point_types.h
pcl::Normal
A point structure representing normal coordinates and the surface curvature estimate.
Definition: point_types.hpp:812
pcl::ism::ImplicitShapeModelEstimation::LocationInfo::point_
PointT point_
Stores the initial point.
Definition: implicit_shape_model.h:278
pcl::features::ISMModel::number_of_classes_
unsigned int number_of_classes_
Stores the number of classes.
Definition: implicit_shape_model.h:217
pcl::features::ISMVoteList
This class is used for storing, analyzing and manipulating votes obtained from ISM algorithm.
Definition: implicit_shape_model.h:76
pcl::ism::ImplicitShapeModelEstimation::training_clouds_
std::vector< typename pcl::PointCloud< PointT >::Ptr > training_clouds_
Stores the clouds used for training.
Definition: implicit_shape_model.h:591
POINT_CLOUD_REGISTER_POINT_STRUCT
POINT_CLOUD_REGISTER_POINT_STRUCT(pcl::_PointXYZLAB,(float, x, x)(float, y, y)(float, z, z)(float, L, L)(float, a, a)(float, b, b)) namespace pcl
Definition: gicp6d.h:79
pcl::features::ISMVoteList::votes_origins_
pcl::PointCloud< PointT >::Ptr votes_origins_
Stores the origins of the votes.
Definition: implicit_shape_model.h:143
pcl::features::ISMVoteList::k_ind_
std::vector< int > k_ind_
Stores neighbours indices.
Definition: implicit_shape_model.h:152
pcl::features::ISMVoteList::votes_
pcl::PointCloud< pcl::InterestPoint >::Ptr votes_
Stores all votes.
Definition: implicit_shape_model.h:137
pcl::ism::ImplicitShapeModelEstimation::number_of_clusters_
unsigned int number_of_clusters_
Number of clusters, is used for clustering descriptors during the training.
Definition: implicit_shape_model.h:611
pcl::ism::ImplicitShapeModelEstimation::VisualWordStat::VisualWordStat
VisualWordStat()
Empty constructor with member variables initialization.
Definition: implicit_shape_model.h:323
pcl::ism::ImplicitShapeModelEstimation::feature_estimator_
Feature::Ptr feature_estimator_
Stores the feature estimator.
Definition: implicit_shape_model.h:608
pcl::features::ISMModel::Ptr
shared_ptr< ISMModel > Ptr
Definition: implicit_shape_model.h:163
pcl::features::ISMModel::descriptors_dimension_
unsigned int descriptors_dimension_
Stores descriptors dimension.
Definition: implicit_shape_model.h:226
pcl::ism::ImplicitShapeModelEstimation::TermCriteria::epsilon_
float epsilon_
Defines the accuracy for k-means clustering.
Definition: implicit_shape_model.h:316
pcl::features::ISMVoteList::votes_class_
std::vector< int > votes_class_
Stores classes for which every single vote was cast.
Definition: implicit_shape_model.h:146
pcl::ism::ImplicitShapeModelEstimation
This class implements Implicit Shape Model algorithm described in "Hough Transforms and 3D SURF for r...
Definition: implicit_shape_model.h:246
pcl::PointCloud
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: projection_matrix.h:52
pcl::ism::ImplicitShapeModelEstimation::FeaturePtr
typename Feature::Ptr FeaturePtr
Definition: implicit_shape_model.h:252
pcl::PointXYZRGB
A point structure representing Euclidean xyz coordinates, and the RGB color.
Definition: point_types.hpp:628
pcl::ism::ImplicitShapeModelEstimation::TermCriteria::max_count_
int max_count_
Defines maximum number of iterations for k-means clustering.
Definition: implicit_shape_model.h:313
pcl::ISMPeak::class_id
int class_id
Determines which class this peak belongs.
Definition: implicit_shape_model.h:66
pcl::ism::ImplicitShapeModelEstimation::VisualWordStat
Structure for storing the visual word.
Definition: implicit_shape_model.h:320
pcl::ism::ImplicitShapeModelEstimation::VisualWordStat::learned_weight_
float learned_weight_
Weight of the vote.
Definition: implicit_shape_model.h:332
pcl::ISMPeak
This struct is used for storing peak.
Definition: implicit_shape_model.h:57
pcl::features::ISMModel::number_of_clusters_
unsigned int number_of_clusters_
Stores the number of clusters.
Definition: implicit_shape_model.h:223
pcl::features::ISMModel::sigmas_
std::vector< float > sigmas_
Stores the sigma value for each class.
Definition: implicit_shape_model.h:205
pcl::features::ISMVoteList::Ptr
shared_ptr< ISMVoteList< PointT > > Ptr
Definition: implicit_shape_model.h:80
pcl::PointXYZ
A point structure representing Euclidean xyz coordinates.
Definition: point_types.hpp:300
pcl::ism::ImplicitShapeModelEstimation::LocationInfo::normal_
NormalT normal_
Stores the normal of the initial point.
Definition: implicit_shape_model.h:281
pcl::ism::ImplicitShapeModelEstimation::training_normals_
std::vector< typename pcl::PointCloud< NormalT >::Ptr > training_normals_
Stores the normals for each training cloud.
Definition: implicit_shape_model.h:597
pcl::ism::ImplicitShapeModelEstimation::LocationInfo::LocationInfo
LocationInfo(unsigned int model_num, const PointT &dir_to_center, const PointT &origin, const NormalT &normal)
Location info constructor.
Definition: implicit_shape_model.h:265
PCL_MAKE_ALIGNED_OPERATOR_NEW
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Definition: memory.h:63
pcl::ism::ImplicitShapeModelEstimation::training_classes_
std::vector< unsigned int > training_classes_
Stores the class number for each cloud from training_clouds_.
Definition: implicit_shape_model.h:594
pcl::InterestPoint
A point structure representing an interest point with Euclidean xyz coordinates, and an interest valu...
Definition: point_types.hpp:778
pcl::ISMPeak::PCL_ADD_POINT4D
PCL_ADD_POINT4D
Point were this peak is located.
Definition: implicit_shape_model.h:60
pcl::ISMPeak::density
double density
Density of this peak.
Definition: implicit_shape_model.h:63
pcl::ism::ImplicitShapeModelEstimation::n_vot_ON_
bool n_vot_ON_
If set to false then Nvot coeff from [Knopp et al., 2010, (4)] is equal 1.0.
Definition: implicit_shape_model.h:614
pcl::ism::ImplicitShapeModelEstimation::LocationInfo::dir_to_center_
PointT dir_to_center_
Expected direction to center for this keypoint.
Definition: implicit_shape_model.h:275
pcl::features::ISMModel::statistical_weights_
std::vector< std::vector< float > > statistical_weights_
Stores statistical weights.
Definition: implicit_shape_model.h:196
pcl::features::ISMVoteList::k_sqr_dist_
std::vector< float > k_sqr_dist_
Stores square distances to the corresponding neighbours.
Definition: implicit_shape_model.h:155
pcl::features::ISMModel::ConstPtr
shared_ptr< const ISMModel > ConstPtr
Definition: implicit_shape_model.h:164
pcl::PointCloud::Ptr
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:428
pcl::ism::ImplicitShapeModelEstimation::sampling_size_
float sampling_size_
This value is used for the simplification.
Definition: implicit_shape_model.h:605
pcl::features::ISMModel::number_of_visual_words_
unsigned int number_of_visual_words_
Stores the number of visual words.
Definition: implicit_shape_model.h:220
pcl::ism::ImplicitShapeModelEstimation::TermCriteria
This structure is used for determining the end of the k-means clustering process.
Definition: implicit_shape_model.h:286
pcl::features::ISMVoteList::tree_
pcl::KdTreeFLANN< pcl::InterestPoint >::Ptr tree_
Stores the search tree.
Definition: implicit_shape_model.h:149
pcl::ism::ImplicitShapeModelEstimation::VisualWordStat::dir_to_center_
pcl::PointXYZ dir_to_center_
Expected direction to center.
Definition: implicit_shape_model.h:335
pcl::Histogram
A point structure representing an N-D histogram.
Definition: point_types.hpp:1677
pcl::features::ISMModel::classes_
std::vector< unsigned int > classes_
Stores the class label for every direction.
Definition: implicit_shape_model.h:202
pcl::PointCloud::ConstPtr
shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:429
pcl::ism::ImplicitShapeModelEstimation::TermCriteria::TermCriteria
TermCriteria(int type, int max_count, float epsilon)
Termination criteria constructor.
Definition: implicit_shape_model.h:299
pcl::features::ISMModel::directions_to_center_
Eigen::MatrixXf directions_to_center_
Stores the directions to objects center for each visual word.
Definition: implicit_shape_model.h:208
pcl::features::ISMModel::clusters_centers_
Eigen::MatrixXf clusters_centers_
Stores the centers of the clusters that were obtained during the visual words clusterization.
Definition: implicit_shape_model.h:211
pcl::features::ISMModel::clusters_
std::vector< std::vector< unsigned int > > clusters_
This is an array of clusters.
Definition: implicit_shape_model.h:214
pcl::features::ISMVoteList::ConstPtr
shared_ptr< const ISMVoteList< PointT > > ConstPtr
Definition: implicit_shape_model.h:81
pcl::features::ISMVoteList::tree_is_valid_
bool tree_is_valid_
Signalizes if the tree is valid.
Definition: implicit_shape_model.h:140
pcl::ism::ImplicitShapeModelEstimation::training_sigmas_
std::vector< float > training_sigmas_
This array stores the sigma values for each training class.
Definition: implicit_shape_model.h:602
pcl::ism::ImplicitShapeModelEstimation::ISMModelPtr
pcl::features::ISMModel::Ptr ISMModelPtr
Definition: implicit_shape_model.h:250
pcl::KdTreeFLANN::Ptr
shared_ptr< KdTreeFLANN< PointT, Dist > > Ptr
Definition: kdtree_flann.h:87
memory.h
Defines functions, macros and traits for allocating and using memory.
PCL_EXPORTS
#define PCL_EXPORTS
Definition: pcl_macros.h:331
pcl::ism::ImplicitShapeModelEstimation::LocationInfo
This structure stores the information about the keypoint.
Definition: implicit_shape_model.h:257
pcl::features::ISMModel
The assignment of this structure is to store the statistical/learned weights and other information of...
Definition: implicit_shape_model.h:161
pcl::Feature
Feature represents the base feature class.
Definition: feature.h:106