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