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