Point Cloud Library (PCL)  1.9.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  * \param in_sigma
108  */
109  void
110  findStrongestPeaks (std::vector<ISMPeak, Eigen::aligned_allocator<ISMPeak> > &out_peaks, int in_class_id, double in_non_maxima_radius, double in_sigma);
111 
112  /** \brief Returns the density at the specified point.
113  * \param[in] point point of interest
114  * \param[in] sigma_dist
115  */
116  double
117  getDensityAtPoint (const PointT &point, double sigma_dist);
118 
119  /** \brief This method simply returns the number of votes. */
120  unsigned int
121  getNumberOfVotes ();
122 
123  protected:
124 
125  /** \brief this method is simply setting up the search tree. */
126  void
127  validateTree ();
128 
129  Eigen::Vector3f
130  shiftMean (const Eigen::Vector3f& snapPt, const double in_dSigmaDist);
131 
132  protected:
133 
134  /** \brief Stores all votes. */
136 
137  /** \brief Signalizes if the tree is valid. */
139 
140  /** \brief Stores the origins of the votes. */
142 
143  /** \brief Stores classes for which every single vote was cast. */
144  std::vector<int> votes_class_;
145 
146  /** \brief Stores the search tree. */
148 
149  /** \brief Stores neighbours indices. */
150  std::vector<int> k_ind_;
151 
152  /** \brief Stores square distances to the corresponding neighbours. */
153  std::vector<float> k_sqr_dist_;
154  };
155 
156  /** \brief The assignment of this structure is to store the statistical/learned weights and other information
157  * of the trained Implict Shape Model algorithm.
158  */
159  struct PCL_EXPORTS 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 
223  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
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 
245  typedef boost::shared_ptr<pcl::features::ISMModel> ISMModelPtr;
246 
247  protected:
248 
249  /** \brief This structure stores the information about the keypoint. */
250  struct PCL_EXPORTS LocationInfo
251  {
252  /** \brief Location info constructor.
253  * \param[in] model_num number of training model.
254  * \param[in] dir_to_center expected direction to center
255  * \param[in] origin initial point
256  * \param[in] normal normal of the initial point
257  */
258  LocationInfo (unsigned int model_num, const PointT& dir_to_center, const PointT& origin, const NormalT& normal) :
259  model_num_ (model_num),
260  dir_to_center_ (dir_to_center),
261  point_ (origin),
262  normal_ (normal) {};
263 
264  /** \brief Tells from which training model this keypoint was extracted. */
265  unsigned int model_num_;
266 
267  /** \brief Expected direction to center for this keypoint. */
269 
270  /** \brief Stores the initial point. */
272 
273  /** \brief Stores the normal of the initial point. */
275  };
276 
277  /** \brief This structure is used for determining the end of the
278  * k-means clustering process. */
279  typedef struct PCL_EXPORTS TC
280  {
281  enum
282  {
283  COUNT = 1,
284  EPS = 2
285  };
286 
287  /** \brief Termination criteria constructor.
288  * \param[in] type defines the condition of termination(max iter., desired accuracy)
289  * \param[in] max_count defines the max number of iterations
290  * \param[in] epsilon defines the desired accuracy
291  */
292  TC(int type, int max_count, float epsilon) :
293  type_ (type),
294  max_count_ (max_count),
295  epsilon_ (epsilon) {};
296 
297  /** \brief Flag that determines when the k-means clustering must be stopped.
298  * If type_ equals COUNT then it must be stopped when the max number of iterations will be
299  * reached. If type_ eaquals EPS then it must be stopped when the desired accuracy will be reached.
300  * These flags can be used together, in that case the clustering will be finished when one of these
301  * conditions will be reached.
302  */
303  int type_;
304 
305  /** \brief Defines maximum number of iterations for k-means clustering. */
307 
308  /** \brief Defines the accuracy for k-means clustering. */
309  float epsilon_;
310  } TermCriteria;
311 
312  /** \brief Structure for storing the visual word. */
313  struct PCL_EXPORTS VisualWordStat
314  {
315  /** \brief Empty constructor with member variables initialization. */
317  class_ (-1),
318  learned_weight_ (0.0f),
319  dir_to_center_ (0.0f, 0.0f, 0.0f) {};
320 
321  /** \brief Which class this vote belongs. */
322  int class_;
323 
324  /** \brief Weight of the vote. */
326 
327  /** \brief Expected direction to center. */
329  };
330 
331  public:
332 
333  /** \brief Simple constructor that initializes everything. */
335 
336  /** \brief Simple destructor. */
337  virtual
339 
340  /** \brief This method simply returns the clouds that were set as the training clouds. */
341  std::vector<typename pcl::PointCloud<PointT>::Ptr>
342  getTrainingClouds ();
343 
344  /** \brief Allows to set clouds for training the ISM model.
345  * \param[in] training_clouds array of point clouds for training
346  */
347  void
348  setTrainingClouds (const std::vector< typename pcl::PointCloud<PointT>::Ptr >& training_clouds);
349 
350  /** \brief Returns the array of classes that indicates which class the corresponding training cloud belongs. */
351  std::vector<unsigned int>
352  getTrainingClasses ();
353 
354  /** \brief Allows to set the class labels for the corresponding training clouds.
355  * \param[in] training_classes array of class labels
356  */
357  void
358  setTrainingClasses (const std::vector<unsigned int>& training_classes);
359 
360  /** \brief This method returns the corresponding cloud of normals for every training point cloud. */
361  std::vector<typename pcl::PointCloud<NormalT>::Ptr>
362  getTrainingNormals ();
363 
364  /** \brief Allows to set normals for the training clouds that were passed through setTrainingClouds method.
365  * \param[in] training_normals array of clouds, each cloud is the cloud of normals
366  */
367  void
368  setTrainingNormals (const std::vector< typename pcl::PointCloud<NormalT>::Ptr >& training_normals);
369 
370  /** \brief Returns the sampling size used for cloud simplification. */
371  float
372  getSamplingSize ();
373 
374  /** \brief Changes the sampling size used for cloud simplification.
375  * \param[in] sampling_size desired size of grid bin
376  */
377  void
378  setSamplingSize (float sampling_size);
379 
380  /** \brief Returns the current feature estimator used for extraction of the descriptors. */
381  boost::shared_ptr<pcl::Feature<PointT, pcl::Histogram<FeatureSize> > >
382  getFeatureEstimator ();
383 
384  /** \brief Changes the feature estimator.
385  * \param[in] feature feature estimator that will be used to extract the descriptors.
386  * Note that it must be fully initialized and configured.
387  */
388  void
389  setFeatureEstimator (boost::shared_ptr<pcl::Feature<PointT, pcl::Histogram<FeatureSize> > > feature);
390 
391  /** \brief Returns the number of clusters used for descriptor clustering. */
392  unsigned int
393  getNumberOfClusters ();
394 
395  /** \brief Changes the number of clusters.
396  * \param num_of_clusters desired number of clusters
397  */
398  void
399  setNumberOfClusters (unsigned int num_of_clusters);
400 
401  /** \brief Returns the array of sigma values. */
402  std::vector<float>
403  getSigmaDists ();
404 
405  /** \brief This method allows to set the value of sigma used for calculating the learned weights for every single class.
406  * \param[in] training_sigmas new sigmas for every class. If you want these values to be computed automatically,
407  * just pass the empty array. The automatic regime calculates the maximum distance between the objects points and takes 10% of
408  * this value as recommended in the article. If there are several objects of the same class,
409  * then it computes the average maximum distance and takes 10%. Note that each class has its own sigma value.
410  */
411  void
412  setSigmaDists (const std::vector<float>& training_sigmas);
413 
414  /** \brief Returns the state of Nvot coeff from [Knopp et al., 2010, (4)],
415  * if set to false then coeff is taken as 1.0. It is just a kind of heuristic.
416  * The default behavior is as in the article. So you can ignore this if you want.
417  */
418  bool
419  getNVotState ();
420 
421  /** \brief Changes the state of the Nvot coeff from [Knopp et al., 2010, (4)].
422  * \param[in] state desired state, if false then Nvot is taken as 1.0
423  */
424  void
425  setNVotState (bool state);
426 
427  /** \brief This method performs training and forms a visual vocabulary. It returns a trained model that
428  * can be saved to file for later usage.
429  * \param[out] trained_model trained model
430  */
431  bool
432  trainISM (ISMModelPtr& trained_model);
433 
434  /** \brief This function is searching for the class of interest in a given cloud
435  * and returns the list of votes.
436  * \param[in] model trained model which will be used for searching the objects
437  * \param[in] in_cloud input cloud that need to be investigated
438  * \param[in] in_normals cloud of normals corresponding to the input cloud
439  * \param[in] in_class_of_interest class which we are looking for
440  */
441  boost::shared_ptr<pcl::features::ISMVoteList<PointT> >
442  findObjects (ISMModelPtr model, typename pcl::PointCloud<PointT>::Ptr in_cloud, typename pcl::PointCloud<Normal>::Ptr in_normals, int in_class_of_interest);
443 
444  protected:
445 
446  /** \brief Extracts the descriptors from the input clouds.
447  * \param[out] histograms it will store the descriptors for each key point
448  * \param[out] locations it will contain the comprehensive information (such as direction, initial keypoint)
449  * for the corresponding descriptors
450  */
451  bool
452  extractDescriptors (std::vector<pcl::Histogram<FeatureSize> >& histograms,
453  std::vector<LocationInfo, Eigen::aligned_allocator<LocationInfo> >& locations);
454 
455  /** \brief This method performs descriptor clustering.
456  * \param[in] histograms descriptors to cluster
457  * \param[out] labels it contains labels for each descriptor
458  * \param[out] clusters_centers stores the centers of clusters
459  */
460  bool
461  clusterDescriptors (std::vector< pcl::Histogram<FeatureSize> >& histograms, Eigen::MatrixXi& labels, Eigen::MatrixXf& clusters_centers);
462 
463  /** \brief This method calculates the value of sigma used for calculating the learned weights for every single class.
464  * \param[out] sigmas computed sigmas.
465  */
466  void
467  calculateSigmas (std::vector<float>& sigmas);
468 
469  /** \brief This function forms a visual vocabulary and evaluates weights
470  * described in [Knopp et al., 2010, (5)].
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] normal_cloud normals for the original point cloud
524  * \param[out] feature_cloud it will store the computed histograms (features) for the given cloud
525  */
526  void
527  estimateFeatures (typename pcl::PointCloud<PointT>::Ptr sampled_point_cloud,
528  typename pcl::PointCloud<NormalT>::Ptr normal_cloud,
529  typename pcl::PointCloud<pcl::Histogram<FeatureSize> >::Ptr feature_cloud);
530 
531  /** \brief Performs K-means clustering.
532  * \param[in] points_to_cluster points to cluster
533  * \param[in] number_of_clusters desired number of clusters
534  * \param[out] io_labels output parameter, which stores the label for each point
535  * \param[in] criteria defines when the computational process need to be finished. For example if the
536  * desired accuracy is achieved or the iteration number exceeds given value
537  * \param[in] attempts number of attempts to compute clustering
538  * \param[in] flags if set to USE_INITIAL_LABELS then initial approximation of labels is taken from io_labels
539  * \param[out] cluster_centers it will store the cluster centers
540  */
541  double
542  computeKMeansClustering (const Eigen::MatrixXf& points_to_cluster,
543  int number_of_clusters,
544  Eigen::MatrixXi& io_labels,
545  TermCriteria criteria,
546  int attempts,
547  int flags,
548  Eigen::MatrixXf& cluster_centers);
549 
550  /** \brief Generates centers for clusters as described in
551  * Arthur, David and Sergei Vassilvitski (2007) k-means++: The Advantages of Careful Seeding.
552  * \param[in] data points to cluster
553  * \param[out] out_centers it will contain generated centers
554  * \param[in] number_of_clusters defines the number of desired cluster centers
555  * \param[in] trials number of trials to generate a center
556  */
557  void
558  generateCentersPP (const Eigen::MatrixXf& data,
559  Eigen::MatrixXf& out_centers,
560  int number_of_clusters,
561  int trials);
562 
563  /** \brief Generates random center for cluster.
564  * \param[in] boxes contains min and max values for each dimension
565  * \param[out] center it will the contain generated center
566  */
567  void
568  generateRandomCenter (const std::vector<Eigen::Vector2f, Eigen::aligned_allocator<Eigen::Vector2f> >& boxes, Eigen::VectorXf& center);
569 
570  /** \brief Computes the square distance between two vectors.
571  * \param[in] vec_1 first vector
572  * \param[in] vec_2 second vector
573  */
574  float
575  computeDistance (Eigen::VectorXf& vec_1, Eigen::VectorXf& vec_2);
576 
577  /** \brief Forbids the assignment operator. */
579  operator= (const ImplicitShapeModelEstimation&);
580 
581  protected:
582 
583  /** \brief Stores the clouds used for training. */
584  std::vector<typename pcl::PointCloud<PointT>::Ptr> training_clouds_;
585 
586  /** \brief Stores the class number for each cloud from training_clouds_. */
587  std::vector<unsigned int> training_classes_;
588 
589  /** \brief Stores the normals for each training cloud. */
590  std::vector<typename pcl::PointCloud<NormalT>::Ptr> training_normals_;
591 
592  /** \brief This array stores the sigma values for each training class. If this array has a size equals 0, then
593  * sigma values will be calculated automatically.
594  */
595  std::vector<float> training_sigmas_;
596 
597  /** \brief This value is used for the simplification. It sets the size of grid bin. */
599 
600  /** \brief Stores the feature estimator. */
601  boost::shared_ptr<pcl::Feature<PointT, pcl::Histogram<FeatureSize> > > feature_estimator_;
602 
603  /** \brief Number of clusters, is used for clustering descriptors during the training. */
604  unsigned int number_of_clusters_;
605 
606  /** \brief If set to false then Nvot coeff from [Knopp et al., 2010, (4)] is equal 1.0. */
607  bool n_vot_ON_;
608 
609  /** \brief This const value is used for indicating that for k-means clustering centers must
610  * be generated as described in
611  * Arthur, David and Sergei Vassilvitski (2007) k-means++: The Advantages of Careful Seeding. */
612  static const int PP_CENTERS = 2;
613 
614  /** \brief This const value is used for indicating that input labels must be taken as the
615  * initial approximation for k-means clustering. */
616  static const int USE_INITIAL_LABELS = 1;
617  };
618  }
619 }
620 
622  (float, x, x)
623  (float, y, y)
624  (float, z, z)
625  (float, density, ism_density)
626  (float, class_id, ism_class_id)
627 )
628 
629 #endif //#ifndef PCL_IMPLICIT_SHAPE_MODEL_H_
pcl::ism::ImplicitShapeModelEstimation::feature_estimator_
boost::shared_ptr< pcl::Feature< PointT, pcl::Histogram< FeatureSize > > > feature_estimator_
Stores the feature estimator.
Definition: implicit_shape_model.h:601
pcl
This file defines compatibility wrappers for low level I/O functions.
Definition: convolution.h:45
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:791
pcl::PointCloud::Ptr
boost::shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:428
pcl::ism::ImplicitShapeModelEstimation::LocationInfo::point_
PointT point_
Stores the initial point.
Definition: implicit_shape_model.h:271
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:77
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:584
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:78
pcl::EIGEN_ALIGN16
struct pcl::PointXYZIEdge EIGEN_ALIGN16
pcl::features::ISMVoteList::votes_origins_
pcl::PointCloud< PointT >::Ptr votes_origins_
Stores the origins of the votes.
Definition: implicit_shape_model.h:141
pcl::features::ISMVoteList::k_ind_
std::vector< int > k_ind_
Stores neighbours indices.
Definition: implicit_shape_model.h:150
pcl::features::ISMVoteList::votes_
pcl::PointCloud< pcl::InterestPoint >::Ptr votes_
Stores all votes.
Definition: implicit_shape_model.h:135
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:604
pcl::ism::ImplicitShapeModelEstimation::VisualWordStat::VisualWordStat
VisualWordStat()
Empty constructor with member variables initialization.
Definition: implicit_shape_model.h:316
pcl::features::ISMModel::descriptors_dimension_
unsigned int descriptors_dimension_
Stores descriptors dimension.
Definition: implicit_shape_model.h:221
pcl::features::ISMVoteList::votes_class_
std::vector< int > votes_class_
Stores classes for which every single vote was cast.
Definition: implicit_shape_model.h:144
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: projection_matrix.h:53
pcl::KdTreeFLANN::Ptr
boost::shared_ptr< KdTreeFLANN< PointT, Dist > > Ptr
Definition: kdtree_flann.h:89
pcl::PointXYZRGB
A point structure representing Euclidean xyz coordinates, and the RGB color.
Definition: point_types.hpp:619
pcl::ISMPeak::class_id
int class_id
Determines which class this peak belongs.
Definition: implicit_shape_model.h:67
pcl::ism::ImplicitShapeModelEstimation::VisualWordStat
Structure for storing the visual word.
Definition: implicit_shape_model.h:313
pcl::ism::ImplicitShapeModelEstimation::VisualWordStat::learned_weight_
float learned_weight_
Weight of the vote.
Definition: implicit_shape_model.h:325
pcl::ism::ImplicitShapeModelEstimation::TC
This structure is used for determining the end of the k-means clustering process.
Definition: implicit_shape_model.h:279
pcl::ism::ImplicitShapeModelEstimation::TC::epsilon_
float epsilon_
Defines the accuracy for k-means clustering.
Definition: implicit_shape_model.h:309
pcl::ISMPeak
This struct is used for storing peak.
Definition: implicit_shape_model.h:58
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::ism::ImplicitShapeModelEstimation::ISMModelPtr
boost::shared_ptr< pcl::features::ISMModel > ISMModelPtr
Definition: implicit_shape_model.h:245
pcl::PointXYZ
A point structure representing Euclidean xyz coordinates.
Definition: point_types.hpp:287
pcl::ism::ImplicitShapeModelEstimation::LocationInfo::normal_
NormalT normal_
Stores the normal of the initial point.
Definition: implicit_shape_model.h:274
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:590
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:258
pcl::ism::ImplicitShapeModelEstimation::TC::TC
TC(int type, int max_count, float epsilon)
Termination criteria constructor.
Definition: implicit_shape_model.h:292
pcl::ism::ImplicitShapeModelEstimation::TC::max_count_
int max_count_
Defines maximum number of iterations for k-means clustering.
Definition: implicit_shape_model.h:306
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:587
pcl::InterestPoint
A point structure representing an interest point with Euclidean xyz coordinates, and an interest valu...
Definition: point_types.hpp:757
pcl::ISMPeak::PCL_ADD_POINT4D
PCL_ADD_POINT4D
Point were this peak is located.
Definition: implicit_shape_model.h:61
pcl::ISMPeak::density
double density
Density of this peak.
Definition: implicit_shape_model.h:64
pcl::ism::ImplicitShapeModelEstimation::TermCriteria
struct PCL_EXPORTS pcl::ism::ImplicitShapeModelEstimation::TC TermCriteria
This structure is used for determining the end of the k-means clustering process.
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:607
pcl::ism::ImplicitShapeModelEstimation::LocationInfo::dir_to_center_
PointT dir_to_center_
Expected direction to center for this keypoint.
Definition: implicit_shape_model.h:268
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:153
pcl::ism::ImplicitShapeModelEstimation::sampling_size_
float sampling_size_
This value is used for the simplification.
Definition: implicit_shape_model.h:598
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::PointCloud::ConstPtr
boost::shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:429
pcl::features::ISMVoteList::tree_
pcl::KdTreeFLANN< pcl::InterestPoint >::Ptr tree_
Stores the search tree.
Definition: implicit_shape_model.h:147
pcl::ism::ImplicitShapeModelEstimation::VisualWordStat::dir_to_center_
pcl::PointXYZ dir_to_center_
Expected direction to center.
Definition: implicit_shape_model.h:328
pcl::Histogram
A point structure representing an N-D histogram.
Definition: point_types.hpp:1523
pcl::features::ISMModel::classes_
std::vector< unsigned int > classes_
Stores the class label for every direction.
Definition: implicit_shape_model.h:197
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::tree_is_valid_
bool tree_is_valid_
Signalizes if the tree is valid.
Definition: implicit_shape_model.h:138
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:595
pcl::ism::ImplicitShapeModelEstimation::LocationInfo
This structure stores the information about the keypoint.
Definition: implicit_shape_model.h:250
pcl::features::ISMModel
The assignment of this structure is to store the statistical/learned weights and other information of...
Definition: implicit_shape_model.h:159
pcl::Feature
Feature represents the base feature class.
Definition: feature.h:105