Point Cloud Library (PCL)  1.14.1-dev
implicit_shape_model.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  */
35 
36 #pragma once
37 
38 #include <vector>
39 #include <fstream>
40 #include <Eigen/src/Core/Matrix.h>
41 #include <pcl/memory.h>
42 #include <pcl/pcl_macros.h>
43 #include <pcl/point_types.h>
44 #include <pcl/point_representation.h>
45 #include <pcl/features/feature.h>
46 #include <pcl/kdtree/kdtree_flann.h> // for KdTreeFLANN
47 
48 namespace pcl
49 {
50  /** \brief This struct is used for storing peak. */
51  struct EIGEN_ALIGN16 ISMPeak
52  {
53  /** \brief Point were this peak is located. */
55 
56  /** \brief Density of this peak. */
57  double density;
58 
59  /** \brief Determines which class this peak belongs. */
60  int class_id;
61 
63  };
64 
65  namespace features
66  {
67  /** \brief This class is used for storing, analyzing and manipulating votes
68  * obtained from ISM algorithm. */
69  template <typename PointT>
71  {
72  public:
73 
74  using Ptr = shared_ptr<ISMVoteList<PointT> >;
75  using ConstPtr = shared_ptr<const ISMVoteList<PointT>>;
76 
77  /** \brief Empty constructor with member variables initialization. */
79 
80  /** \brief virtual descriptor. */
81  virtual
82  ~ISMVoteList ();
83 
84  /** \brief This method simply adds another vote to the list.
85  * \param[in] in_vote vote to add
86  * \param[in] vote_origin origin of the added vote
87  * \param[in] in_class class for which this vote is cast
88  */
89  void
90  addVote (pcl::InterestPoint& in_vote, const PointT &vote_origin, int in_class);
91 
92  /** \brief Returns the colored cloud that consists of votes for center (blue points) and
93  * initial point cloud (if it was passed).
94  * \param[in] cloud cloud that needs to be merged with votes for visualizing. */
96  getColoredCloud (typename pcl::PointCloud<PointT>::Ptr cloud = 0);
97 
98  /** \brief This method finds the strongest peaks (points were density has most higher values).
99  * It is based on the non maxima suppression principles.
100  * \param[out] out_peaks it will contain the strongest peaks
101  * \param[in] in_class_id class of interest for which peaks are evaluated
102  * \param[in] in_non_maxima_radius non maxima suppression radius. The shapes radius is recommended for this value.
103  * \param in_sigma
104  */
105  void
106  findStrongestPeaks (std::vector<ISMPeak, Eigen::aligned_allocator<ISMPeak> > &out_peaks, int in_class_id, double in_non_maxima_radius, double in_sigma);
107 
108  /** \brief Returns the density at the specified point.
109  * \param[in] point point of interest
110  * \param[in] sigma_dist
111  */
112  double
113  getDensityAtPoint (const PointT &point, double sigma_dist);
114 
115  /** \brief This method simply returns the number of votes. */
116  unsigned int
117  getNumberOfVotes ();
118 
119  protected:
120 
121  /** \brief this method is simply setting up the search tree. */
122  void
123  validateTree ();
124 
125  Eigen::Vector3f
126  shiftMean (const Eigen::Vector3f& snapPt, const double in_dSigmaDist);
127 
128  protected:
129 
130  /** \brief Stores all votes. */
132 
133  /** \brief Signalizes if the tree is valid. */
134  bool tree_is_valid_{false};
135 
136  /** \brief Stores the origins of the votes. */
138 
139  /** \brief Stores classes for which every single vote was cast. */
140  std::vector<int> votes_class_{};
141 
142  /** \brief Stores the search tree. */
144 
145  /** \brief Stores neighbours indices. */
146  pcl::Indices k_ind_{};
147 
148  /** \brief Stores square distances to the corresponding neighbours. */
149  std::vector<float> k_sqr_dist_{};
150  };
151 
152  /** \brief The assignment of this structure is to store the statistical/learned weights and other information
153  * of the trained Implicit Shape Model algorithm.
154  */
156  {
157  using Ptr = shared_ptr<ISMModel>;
158  using ConstPtr = shared_ptr<const ISMModel>;
159 
160  /** \brief Simple constructor that initializes the structure. */
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_{0};
212 
213  /** \brief Stores the number of visual words. */
214  unsigned int number_of_visual_words_{0};
215 
216  /** \brief Stores the number of clusters. */
217  unsigned int number_of_clusters_{0};
218 
219  /** \brief Stores descriptors dimension. */
220  unsigned int descriptors_dimension_{0};
221 
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 classification"
230  * by Jan Knopp, Mukta Prasad, Geert Willems, 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 classification"
235  * by Jan Knopp, Mukta Prasad, Geert Willems, Radu Timofte, and Luc Van Gool
236  *
237  * Authors: Roman Shapovalov, Alexander Velizhev, Sergey Ushakov
238  * \ingroup recognition
239  */
240  template <int FeatureSize, typename PointT, typename NormalT = pcl::Normal>
242  {
243  public:
244 
247  using FeaturePtr = typename Feature::Ptr;
248 
249  protected:
250 
251  /** \brief This structure stores the information about the keypoint. */
253  {
254  /** \brief Location info constructor.
255  * \param[in] model_num number of training model.
256  * \param[in] dir_to_center expected direction to center
257  * \param[in] origin initial point
258  * \param[in] normal normal of the initial point
259  */
260  LocationInfo (unsigned int model_num, const PointT& dir_to_center, const PointT& origin, const NormalT& normal) :
261  model_num_ (model_num),
262  dir_to_center_ (dir_to_center),
263  point_ (origin),
264  normal_ (normal) {};
265 
266  /** \brief Tells from which training model this keypoint was extracted. */
267  unsigned int model_num_;
268 
269  /** \brief Expected direction to center for this keypoint. */
271 
272  /** \brief Stores the initial point. */
274 
275  /** \brief Stores the normal of the initial point. */
277  };
278 
279  /** \brief This structure is used for determining the end of the
280  * k-means clustering process. */
282  {
283  enum
284  {
285  COUNT = 1,
286  EPS = 2
287  };
288 
289  /** \brief Termination criteria constructor.
290  * \param[in] type defines the condition of termination(max iter., desired accuracy)
291  * \param[in] max_count defines the max number of iterations
292  * \param[in] epsilon defines the desired accuracy
293  */
294  TermCriteria(int type, int max_count, float epsilon) :
295  type_ (type),
296  max_count_ (max_count),
297  epsilon_ (epsilon) {};
298 
299  /** \brief Flag that determines when the k-means clustering must be stopped.
300  * If type_ equals COUNT then it must be stopped when the max number of iterations will be
301  * reached. If type_ eaquals EPS then it must be stopped when the desired accuracy will be reached.
302  * These flags can be used together, in that case the clustering will be finished when one of these
303  * conditions will be reached.
304  */
305  int type_;
306 
307  /** \brief Defines maximum number of iterations for k-means clustering. */
309 
310  /** \brief Defines the accuracy for k-means clustering. */
311  float epsilon_;
312  };
313 
314  /** \brief Structure for storing the visual word. */
316  {
317  /** \brief Empty constructor with member variables initialization. */
319 
320  dir_to_center_ (0.0f, 0.0f, 0.0f) {};
321 
322  /** \brief Which class this vote belongs. */
323  int class_{-1};
324 
325  /** \brief Weight of the vote. */
326  float learned_weight_{0.0f};
327 
328  /** \brief Expected direction to center. */
330  };
331 
332  public:
333 
334  /** \brief Simple constructor that initializes everything. */
336 
337  /** \brief Simple destructor. */
338  virtual
340 
341  /** \brief This method simply returns the clouds that were set as the training clouds. */
342  std::vector<typename pcl::PointCloud<PointT>::Ptr>
343  getTrainingClouds ();
344 
345  /** \brief Allows to set clouds for training the ISM model.
346  * \param[in] training_clouds array of point clouds for training
347  */
348  void
349  setTrainingClouds (const std::vector< typename pcl::PointCloud<PointT>::Ptr >& training_clouds);
350 
351  /** \brief Returns the array of classes that indicates which class the corresponding training cloud belongs. */
352  std::vector<unsigned int>
353  getTrainingClasses ();
354 
355  /** \brief Allows to set the class labels for the corresponding training clouds.
356  * \param[in] training_classes array of class labels
357  */
358  void
359  setTrainingClasses (const std::vector<unsigned int>& training_classes);
360 
361  /** \brief This method returns the corresponding cloud of normals for every training point cloud. */
362  std::vector<typename pcl::PointCloud<NormalT>::Ptr>
363  getTrainingNormals ();
364 
365  /** \brief Allows to set normals for the training clouds that were passed through setTrainingClouds method.
366  * \param[in] training_normals array of clouds, each cloud is the cloud of normals
367  */
368  void
369  setTrainingNormals (const std::vector< typename pcl::PointCloud<NormalT>::Ptr >& training_normals);
370 
371  /** \brief Returns the sampling size used for cloud simplification. */
372  float
373  getSamplingSize ();
374 
375  /** \brief Changes the sampling size used for cloud simplification.
376  * \param[in] sampling_size desired size of grid bin
377  */
378  void
379  setSamplingSize (float sampling_size);
380 
381  /** \brief Returns the current feature estimator used for extraction of the descriptors. */
382  FeaturePtr
383  getFeatureEstimator ();
384 
385  /** \brief Changes the feature estimator.
386  * \param[in] feature feature estimator that will be used to extract the descriptors.
387  * Note that it must be fully initialized and configured.
388  */
389  void
390  setFeatureEstimator (FeaturePtr feature);
391 
392  /** \brief Returns the number of clusters used for descriptor clustering. */
393  unsigned int
394  getNumberOfClusters ();
395 
396  /** \brief Changes the number of clusters.
397  * \param num_of_clusters desired number of clusters
398  */
399  void
400  setNumberOfClusters (unsigned int num_of_clusters);
401 
402  /** \brief Returns the array of sigma values. */
403  std::vector<float>
404  getSigmaDists ();
405 
406  /** \brief This method allows to set the value of sigma used for calculating the learned weights for every single class.
407  * \param[in] training_sigmas new sigmas for every class. If you want these values to be computed automatically,
408  * just pass the empty array. The automatic regime calculates the maximum distance between the objects points and takes 10% of
409  * this value as recommended in the article. If there are several objects of the same class,
410  * then it computes the average maximum distance and takes 10%. Note that each class has its own sigma value.
411  */
412  void
413  setSigmaDists (const std::vector<float>& training_sigmas);
414 
415  /** \brief Returns the state of Nvot coeff from [Knopp et al., 2010, (4)],
416  * if set to false then coeff is taken as 1.0. It is just a kind of heuristic.
417  * The default behavior is as in the article. So you can ignore this if you want.
418  */
419  bool
420  getNVotState ();
421 
422  /** \brief Changes the state of the Nvot coeff from [Knopp et al., 2010, (4)].
423  * \param[in] state desired state, if false then Nvot is taken as 1.0
424  */
425  void
426  setNVotState (bool state);
427 
428  /** \brief This method performs training and forms a visual vocabulary. It returns a trained model that
429  * can be saved to file for later usage.
430  * \param[out] trained_model trained model
431  */
432  bool
433  trainISM (ISMModelPtr& trained_model);
434 
435  /** \brief This function is searching for the class of interest in a given cloud
436  * and returns the list of votes.
437  * \param[in] model trained model which will be used for searching the objects
438  * \param[in] in_cloud input cloud that need to be investigated
439  * \param[in] in_normals cloud of normals corresponding to the input cloud
440  * \param[in] in_class_of_interest class which we are looking for
441  */
443  findObjects (ISMModelPtr model, typename pcl::PointCloud<PointT>::Ptr in_cloud, typename pcl::PointCloud<Normal>::Ptr in_normals, int in_class_of_interest);
444 
445  protected:
446 
447  /** \brief Extracts the descriptors from the input clouds.
448  * \param[out] histograms it will store the descriptors for each key point
449  * \param[out] locations it will contain the comprehensive information (such as direction, initial keypoint)
450  * for the corresponding descriptors
451  */
452  bool
453  extractDescriptors (std::vector<pcl::Histogram<FeatureSize> >& histograms,
454  std::vector<LocationInfo, Eigen::aligned_allocator<LocationInfo> >& locations);
455 
456  /** \brief This method performs descriptor clustering.
457  * \param[in] histograms descriptors to cluster
458  * \param[out] labels it contains labels for each descriptor
459  * \param[out] clusters_centers stores the centers of clusters
460  */
461  bool
462  clusterDescriptors (std::vector< pcl::Histogram<FeatureSize> >& histograms, Eigen::MatrixXi& labels, Eigen::MatrixXf& clusters_centers);
463 
464  /** \brief This method calculates the value of sigma used for calculating the learned weights for every single class.
465  * \param[out] sigmas computed sigmas.
466  */
467  void
468  calculateSigmas (std::vector<float>& sigmas);
469 
470  /** \brief This function forms a visual vocabulary and evaluates weights
471  * described in [Knopp et al., 2010, (5)].
472  * \param[in] locations array containing description of each keypoint: its position, which cloud belongs
473  * and expected direction to center
474  * \param[in] labels labels that were obtained during k-means clustering
475  * \param[in] sigmas array of sigmas for each class
476  * \param[in] clusters clusters that were obtained during k-means clustering
477  * \param[out] statistical_weights stores the computed statistical weights
478  * \param[out] learned_weights stores the computed learned weights
479  */
480  void
481  calculateWeights (const std::vector< LocationInfo, Eigen::aligned_allocator<LocationInfo> >& locations,
482  const Eigen::MatrixXi &labels,
483  std::vector<float>& sigmas,
484  std::vector<std::vector<unsigned int> >& clusters,
485  std::vector<std::vector<float> >& statistical_weights,
486  std::vector<float>& learned_weights);
487 
488  /** \brief Simplifies the cloud using voxel grid principles.
489  * \param[in] in_point_cloud cloud that need to be simplified
490  * \param[in] in_normal_cloud normals of the cloud that need to be simplified
491  * \param[out] out_sampled_point_cloud simplified cloud
492  * \param[out] out_sampled_normal_cloud and the corresponding normals
493  */
494  void
495  simplifyCloud (typename pcl::PointCloud<PointT>::ConstPtr in_point_cloud,
496  typename pcl::PointCloud<NormalT>::ConstPtr in_normal_cloud,
497  typename pcl::PointCloud<PointT>::Ptr out_sampled_point_cloud,
498  typename pcl::PointCloud<NormalT>::Ptr out_sampled_normal_cloud);
499 
500  /** \brief This method simply shifts the clouds points relative to the passed point.
501  * \param[in] in_cloud cloud to shift
502  * \param[in] shift_point point relative to which the cloud will be shifted
503  */
504  void
505  shiftCloud (typename pcl::PointCloud<PointT>::Ptr in_cloud, Eigen::Vector3f shift_point);
506 
507  /** \brief This method simply computes the rotation matrix, so that the given normal
508  * would match the Y axis after the transformation. This is done because the algorithm needs to be invariant
509  * to the affine transformations.
510  * \param[in] in_normal normal for which the rotation matrix need to be computed
511  */
512  Eigen::Matrix3f
513  alignYCoordWithNormal (const NormalT& in_normal);
514 
515  /** \brief This method applies transform set in in_transform to vector io_vector.
516  * \param[in] io_vec vector that need to be transformed
517  * \param[in] in_transform matrix that contains the transformation
518  */
519  void
520  applyTransform (Eigen::Vector3f& io_vec, const Eigen::Matrix3f& in_transform);
521 
522  /** \brief This method estimates features for the given point cloud.
523  * \param[in] sampled_point_cloud sampled point cloud for which the features must be computed
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, Eigen::aligned_allocator<Eigen::Vector2f> >& boxes, Eigen::VectorXf& center);
570 
571  /** \brief Computes the square distance between 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. */
599  float sampling_size_{0.1f};
600 
601  /** \brief Stores the feature estimator. */
603 
604  /** \brief Number of clusters, is used for clustering descriptors during the training. */
605  unsigned int number_of_clusters_{184};
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_{true};
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 )
Feature represents the base feature class.
Definition: feature.h:107
shared_ptr< Feature< PointInT, PointOutT > > Ptr
Definition: feature.h:114
shared_ptr< KdTreeFLANN< PointT, Dist > > Ptr
Definition: kdtree_flann.h:151
shared_ptr< PointCloud< PointT > > Ptr
Definition: point_cloud.h:413
shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:414
This class is used for storing, analyzing and manipulating votes obtained from ISM algorithm.
shared_ptr< ISMVoteList< PointT > > Ptr
shared_ptr< const ISMVoteList< PointT > > ConstPtr
ISMVoteList()
Empty constructor with member variables initialization.
This class implements Implicit Shape Model algorithm described in "Hough Transforms and 3D SURF for r...
pcl::features::ISMModel::Ptr ISMModelPtr
ImplicitShapeModelEstimation()
Simple constructor that initializes everything.
Feature::Ptr feature_estimator_
Stores the feature estimator.
Defines all the PCL implemented PointT point type structures.
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Definition: memory.h:86
Defines functions, macros and traits for allocating and using memory.
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:133
Defines all the PCL and non-PCL macros used.
#define PCL_EXPORTS
Definition: pcl_macros.h:325
A point structure representing an N-D histogram.
This struct is used for storing peak.
PCL_ADD_POINT4D
Point were this peak is located.
double density
Density of this peak.
int class_id
Determines which class this peak belongs.
A point structure representing an interest point with Euclidean xyz coordinates, and an interest valu...
A point structure representing normal coordinates and the surface curvature estimate.
A point structure representing Euclidean xyz coordinates.
A point structure representing Euclidean xyz coordinates, and the RGB color.
The assignment of this structure is to store the statistical/learned weights and other information of...
shared_ptr< ISMModel > Ptr
shared_ptr< const ISMModel > ConstPtr
Eigen::MatrixXf clusters_centers_
Stores the centers of the clusters that were obtained during the visual words clusterization.
ISMModel()
Simple constructor that initializes the structure.
Eigen::MatrixXf directions_to_center_
Stores the directions to objects center for each visual word.
This structure stores the information about the keypoint.
NormalT normal_
Stores the normal of the initial point.
unsigned int model_num_
Tells from which training model this keypoint was extracted.
LocationInfo(unsigned int model_num, const PointT &dir_to_center, const PointT &origin, const NormalT &normal)
Location info constructor.
PointT dir_to_center_
Expected direction to center for this keypoint.
This structure is used for determining the end of the k-means clustering process.
int type_
Flag that determines when the k-means clustering must be stopped.
float epsilon_
Defines the accuracy for k-means clustering.
TermCriteria(int type, int max_count, float epsilon)
Termination criteria constructor.
int max_count_
Defines maximum number of iterations for k-means clustering.
pcl::PointXYZ dir_to_center_
Expected direction to center.
VisualWordStat()
Empty constructor with member variables initialization.