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