This class implements Implicit Shape Model algorithm described in "Hough Transforms and 3D SURF for robust three dimensional classication" by Jan Knopp1, Mukta Prasad, Geert Willems1, Radu Timofte, and Luc Van Gool. It has two main member functions. One for training, using the data for which we know which class it belongs to. And second for investigating a cloud for the presence of the class of interest. Implementation of the ISM algorithm described in "Hough Transforms and 3D SURF for robust three dimensional classication" by Jan Knopp, Mukta Prasad, Geert Willems, Radu Timofte, and Luc Van Gool. More...
#include <implicit_shape_model.h>
Classes | |
struct | LocationInfo |
This structure stores the information about the keypoint. More... | |
struct | TC |
This structure is used for determining the end of the k-means clustering process. More... | |
struct | VisualWordStat |
Structure for storing the visual word. More... | |
Public Types | |
typedef boost::shared_ptr < pcl::features::ISMModel > | ISMModelPtr |
Public Member Functions | |
boost::shared_ptr < pcl::features::ISMVoteList < PointT > > | findObjects (ISMModelPtr model, typename pcl::PointCloud< PointT >::Ptr in_cloud, typename pcl::PointCloud< Normal >::Ptr in_normals, int in_class_of_interest) |
This function is searching for the class of interest in a given cloud and returns the list of votes. | |
boost::shared_ptr < pcl::Feature< PointT, pcl::Histogram< FeatureSize > > > | getFeatureEstimator () |
Returns the current feature estimator used for extraction of the descriptors. | |
unsigned int | getNumberOfClusters () |
Returns the number of clusters used for descriptor clustering. | |
bool | getNVotState () |
Returns the state of Nvot coeff from [Knopp et al., 2010, (4)], if set to false then coeff is taken as 1.0. It is just a kind of heuristic. The default behavior is as in the article. So you can ignore this if you want. | |
float | getSamplingSize () |
Returns the sampling size used for cloud simplification. | |
std::vector< float > | getSigmaDists () |
Returns the array of sigma values. | |
std::vector< unsigned int > | getTrainingClasses () |
Returns the array of classes that indicates which class the corresponding training cloud belongs. | |
std::vector< typename pcl::PointCloud< PointT >::Ptr > | getTrainingClouds () |
This method simply returns the clouds that were set as the training clouds. | |
std::vector< typename pcl::PointCloud< NormalT > ::Ptr > | getTrainingNormals () |
This method returns the coresponding cloud of normals for every training point cloud. | |
ImplicitShapeModelEstimation () | |
Simple constructor that initializes everything. | |
void | setFeatureEstimator (boost::shared_ptr< pcl::Feature< PointT, pcl::Histogram< FeatureSize > > > feature) |
Changes the feature estimator. | |
void | setNumberOfClusters (unsigned int num_of_clusters) |
Changes the number of clusters. | |
void | setNVotState (bool state) |
Changes the state of the Nvot coeff from [Knopp et al., 2010, (4)]. | |
void | setSamplingSize (float sampling_size) |
Changes the sampling size used for cloud simplification. | |
void | setSigmaDists (const std::vector< float > &training_sigmas) |
This method allows to set the value of sigma used for calculating the learned weights for every single class. | |
void | setTrainingClasses (const std::vector< unsigned int > &training_classes) |
Allows to set the class labels for the corresponding training clouds. | |
void | setTrainingClouds (const std::vector< typename pcl::PointCloud< PointT >::Ptr > &training_clouds) |
Allows to set clouds for training the ISM model. | |
void | setTrainingNormals (const std::vector< typename pcl::PointCloud< NormalT >::Ptr > &training_normals) |
Allows to set normals for the training clouds that were passed through setTrainingClouds method. | |
bool | trainISM (ISMModelPtr &trained_model) |
This method performs training and forms a visual vocabulary. It returns a trained model that can be saved to file for later usage. | |
virtual | ~ImplicitShapeModelEstimation () |
Simple destructor. | |
Protected Types | |
typedef struct PCL_EXPORTS pcl::ism::ImplicitShapeModelEstimation::TC | TermCriteria |
This structure is used for determining the end of the k-means clustering process. | |
Protected Member Functions | |
Eigen::Matrix3f | alignYCoordWithNormal (const NormalT &in_normal) |
This method simply computes the rotation matrix, so that the given normal would match the Y axis after the transformation. This is done because the algorithm needs to be invariant to the affine transformations. | |
void | applyTransform (Eigen::Vector3f &io_vec, const Eigen::Matrix3f &in_transform) |
This method applies transform set in in_transform to vector io_vector. | |
void | calculateSigmas (std::vector< float > &sigmas) |
This method calculates the value of sigma used for calculating the learned weights for every single class. | |
void | calculateWeights (const std::vector< LocationInfo, Eigen::aligned_allocator< LocationInfo > > &locations, const Eigen::MatrixXi &labels, std::vector< float > &sigmas, std::vector< std::vector< unsigned int > > &clusters, std::vector< std::vector< float > > &statistical_weights, std::vector< float > &learned_weights) |
This function forms a visual vocabulary and evaluates weights described in [Knopp et al., 2010, (5)]. | |
bool | clusterDescriptors (std::vector< pcl::Histogram< FeatureSize > > &histograms, Eigen::MatrixXi &labels, Eigen::MatrixXf &clusters_centers) |
This method performs descriptor clustering. | |
float | computeDistance (Eigen::VectorXf &vec_1, Eigen::VectorXf &vec_2) |
Computes the square distance beetween two vectors. | |
double | computeKMeansClustering (const Eigen::MatrixXf &points_to_cluster, int number_of_clusters, Eigen::MatrixXi &io_labels, TermCriteria criteria, int attempts, int flags, Eigen::MatrixXf &cluster_centers) |
Performs K-means clustering. | |
void | estimateFeatures (typename pcl::PointCloud< PointT >::Ptr sampled_point_cloud, typename pcl::PointCloud< NormalT >::Ptr normal_cloud, typename pcl::PointCloud< pcl::Histogram< FeatureSize > >::Ptr feature_cloud) |
This method estimates features for the given point cloud. | |
bool | extractDescriptors (std::vector< pcl::Histogram< FeatureSize > > &histograms, std::vector< LocationInfo, Eigen::aligned_allocator< LocationInfo > > &locations) |
Extracts the descriptors from the input clouds. | |
void | generateCentersPP (const Eigen::MatrixXf &data, Eigen::MatrixXf &out_centers, int number_of_clusters, int trials) |
Generates centers for clusters as described in Arthur, David and Sergei Vassilvitski (2007) k-means++: The Advantages of Careful Seeding. | |
void | generateRandomCenter (const std::vector< Eigen::Vector2f > &boxes, Eigen::VectorXf ¢er) |
Generates random center for cluster. | |
ImplicitShapeModelEstimation & | operator= (const ImplicitShapeModelEstimation &) |
Forbids the assignment operator. | |
void | shiftCloud (typename pcl::PointCloud< PointT >::Ptr in_cloud, Eigen::Vector3f shift_point) |
This method simply shifts the clouds points relative to the passed point. | |
void | simplifyCloud (typename pcl::PointCloud< PointT >::ConstPtr in_point_cloud, typename pcl::PointCloud< NormalT >::ConstPtr in_normal_cloud, typename pcl::PointCloud< PointT >::Ptr out_sampled_point_cloud, typename pcl::PointCloud< NormalT >::Ptr out_sampled_normal_cloud) |
Simplifies the cloud using voxel grid principles. | |
Protected Attributes | |
boost::shared_ptr < pcl::Feature< PointT, pcl::Histogram< FeatureSize > > > | feature_estimator_ |
Stores the feature estimator. | |
bool | n_vot_ON_ |
If set to false then Nvot coeff from [Knopp et al., 2010, (4)] is equal 1.0. | |
unsigned int | number_of_clusters_ |
Number of clusters, is used for clustering descriptors during the training. | |
float | sampling_size_ |
This value is used for the simplification. It sets the size of grid bin. | |
std::vector< unsigned int > | training_classes_ |
Stores the class number for each cloud from training_clouds_. | |
std::vector< typename pcl::PointCloud< PointT >::Ptr > | training_clouds_ |
Stores the clouds used for training. | |
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. If this array has a size equals 0, then sigma values will be calculated automatically. | |
Static Protected Attributes | |
static const int | PP_CENTERS = 2 |
This const value is used for indicating that for k-means clustering centers must be generated as described in Arthur, David and Sergei Vassilvitski (2007) k-means++: The Advantages of Careful Seeding. | |
static const int | USE_INITIAL_LABELS = 1 |
This const value is used for indicating that input labels must be taken as the initial approximation for k-means clustering. |
This class implements Implicit Shape Model algorithm described in "Hough Transforms and 3D SURF for robust three dimensional classication" by Jan Knopp1, Mukta Prasad, Geert Willems1, Radu Timofte, and Luc Van Gool. It has two main member functions. One for training, using the data for which we know which class it belongs to. And second for investigating a cloud for the presence of the class of interest. Implementation of the ISM algorithm described in "Hough Transforms and 3D SURF for robust three dimensional classication" by Jan Knopp, Mukta Prasad, Geert Willems, Radu Timofte, and Luc Van Gool.
Authors: Roman Shapovalov, Alexander Velizhev, Sergey Ushakov
Definition at line 240 of file implicit_shape_model.h.
typedef boost::shared_ptr<pcl::features::ISMModel> pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::ISMModelPtr |
Definition at line 244 of file implicit_shape_model.h.
typedef struct PCL_EXPORTS pcl::ism::ImplicitShapeModelEstimation::TC pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::TermCriteria [protected] |
This structure is used for determining the end of the k-means clustering process.
pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::ImplicitShapeModelEstimation | ( | ) |
Simple constructor that initializes everything.
Definition at line 550 of file implicit_shape_model.hpp.
pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::~ImplicitShapeModelEstimation | ( | ) | [virtual] |
Simple destructor.
Definition at line 564 of file implicit_shape_model.hpp.
Eigen::Matrix3f pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::alignYCoordWithNormal | ( | const NormalT & | in_normal | ) | [protected] |
This method simply computes the rotation matrix, so that the given normal would match the Y axis after the transformation. This is done because the algorithm needs to be invariant to the affine transformations.
[in] | in_normal | normal for which the rotation matrix need to be computed |
Definition at line 1202 of file implicit_shape_model.hpp.
void pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::applyTransform | ( | Eigen::Vector3f & | io_vec, |
const Eigen::Matrix3f & | in_transform | ||
) | [protected] |
This method applies transform set in in_transform to vector io_vector.
[in] | io_vec | vector that need to be transformed |
[in] | in_transform | matrix that contains the transformation |
Definition at line 1233 of file implicit_shape_model.hpp.
void pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::calculateSigmas | ( | std::vector< float > & | sigmas | ) | [protected] |
This method calculates the value of sigma used for calculating the learned weights for every single class.
[out] | sigmas | computed sigmas. |
Definition at line 942 of file implicit_shape_model.hpp.
void pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::calculateWeights | ( | const std::vector< LocationInfo, Eigen::aligned_allocator< LocationInfo > > & | locations, |
const Eigen::MatrixXi & | labels, | ||
std::vector< float > & | sigmas, | ||
std::vector< std::vector< unsigned int > > & | clusters, | ||
std::vector< std::vector< float > > & | statistical_weights, | ||
std::vector< float > & | learned_weights | ||
) | [protected] |
This function forms a visual vocabulary and evaluates weights described in [Knopp et al., 2010, (5)].
[in] | classes | classes that we want to learn |
[in] | locations | array containing description of each keypoint: its position, which cloud belongs and expected direction to center |
[in] | labels | labels that were obtained during k-means clustering |
[in] | sigmas | array of sigmas for each class |
[in] | clusters | clusters that were obtained during k-means clustering |
[out] | statistical_weights | stores the computed statistical weights |
[out] | learned_weights | stores the computed learned weights |
Definition at line 993 of file implicit_shape_model.hpp.
bool pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::clusterDescriptors | ( | std::vector< pcl::Histogram< FeatureSize > > & | histograms, |
Eigen::MatrixXi & | labels, | ||
Eigen::MatrixXf & | clusters_centers | ||
) | [protected] |
This method performs descriptor clustering.
[in] | histograms | descriptors to cluster |
[out] | labels | it contains labels for each descriptor |
[out] | cluster_centers | stores the centers of clusters |
Definition at line 916 of file implicit_shape_model.hpp.
float pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::computeDistance | ( | Eigen::VectorXf & | vec_1, |
Eigen::VectorXf & | vec_2 | ||
) | [protected] |
Computes the square distance beetween two vectors.
[in] | vec_1 | first vector |
[in] | vec_2 | second vector |
Definition at line 1523 of file implicit_shape_model.hpp.
double pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::computeKMeansClustering | ( | const Eigen::MatrixXf & | points_to_cluster, |
int | number_of_clusters, | ||
Eigen::MatrixXi & | io_labels, | ||
TermCriteria | criteria, | ||
int | attempts, | ||
int | flags, | ||
Eigen::MatrixXf & | cluster_centers | ||
) | [protected] |
Performs K-means clustering.
[in] | points_to_cluster | points to cluster |
[in] | number_of_clusters | desired number of clusters |
[out] | io_labels | output parameter, which stores the label for each point |
[in] | criteria | defines when the computational process need to be finished. For example if the desired accuracy is achieved or the iteration number exceeds given value |
[in] | attempts | number of attempts to compute clustering |
[in] | flags | if set to USE_INITIAL_LABELS then initial approximation of labels is taken from io_labels |
[out] | cluster_centers | it will store the cluster centers |
Definition at line 1265 of file implicit_shape_model.hpp.
void pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::estimateFeatures | ( | typename pcl::PointCloud< PointT >::Ptr | sampled_point_cloud, |
typename pcl::PointCloud< NormalT >::Ptr | normal_cloud, | ||
typename pcl::PointCloud< pcl::Histogram< FeatureSize > >::Ptr | feature_cloud | ||
) | [protected] |
This method estimates features for the given point cloud.
[in] | sampled_point_cloud | sampled point cloud for which the features must be computed |
[in] | point_cloud | original point cloud |
[in] | normal_cloud | normals for the original point cloud |
[out] | feature_cloud | it will store the computed histograms (features) for the given cloud |
Definition at line 1240 of file implicit_shape_model.hpp.
bool pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::extractDescriptors | ( | std::vector< pcl::Histogram< FeatureSize > > & | histograms, |
std::vector< LocationInfo, Eigen::aligned_allocator< LocationInfo > > & | locations | ||
) | [protected] |
Extracts the descriptors from the input clouds.
[out] | histograms | it will store the descriptors for each key point |
[out] | locations | it will contain the comprehensive information (such as direction, initial keypoint) for the corresponding descriptors |
Definition at line 849 of file implicit_shape_model.hpp.
boost::shared_ptr< pcl::features::ISMVoteList< PointT > > pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::findObjects | ( | ISMModelPtr | model, |
typename pcl::PointCloud< PointT >::Ptr | in_cloud, | ||
typename pcl::PointCloud< Normal >::Ptr | in_normals, | ||
int | in_class_of_interest | ||
) |
This function is searching for the class of interest in a given cloud and returns the list of votes.
[in] | model | trained model which will be used for searching the objects |
[in] | in_cloud | input cloud that need to be investigated |
[in] | in_normals | cloud of normals coresponding to the input cloud |
[in] | in_class_of_interest | class which we are looking for |
Definition at line 754 of file implicit_shape_model.hpp.
void pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::generateCentersPP | ( | const Eigen::MatrixXf & | data, |
Eigen::MatrixXf & | out_centers, | ||
int | number_of_clusters, | ||
int | trials | ||
) | [protected] |
Generates centers for clusters as described in Arthur, David and Sergei Vassilvitski (2007) k-means++: The Advantages of Careful Seeding.
[in] | data | points to cluster |
[out] | out_centers | it will contain generated centers |
[in] | number_of_clusters | defines the number of desired cluster centers |
[in] | trials | number of trials to generate a center |
Definition at line 1431 of file implicit_shape_model.hpp.
void pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::generateRandomCenter | ( | const std::vector< Eigen::Vector2f > & | boxes, |
Eigen::VectorXf & | center | ||
) | [protected] |
Generates random center for cluster.
[in] | boxes | contains min and max values for each dimension |
[out] | center | it will the contain generated center |
Definition at line 1507 of file implicit_shape_model.hpp.
boost::shared_ptr< pcl::Feature< PointT, pcl::Histogram< FeatureSize > > > pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::getFeatureEstimator | ( | ) |
Returns the current feature estimator used for extraction of the descriptors.
Definition at line 640 of file implicit_shape_model.hpp.
unsigned int pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::getNumberOfClusters | ( | ) |
Returns the number of clusters used for descriptor clustering.
Definition at line 655 of file implicit_shape_model.hpp.
bool pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::getNVotState | ( | ) |
Returns the state of Nvot coeff from [Knopp et al., 2010, (4)], if set to false then coeff is taken as 1.0. It is just a kind of heuristic. The default behavior is as in the article. So you can ignore this if you want.
Definition at line 686 of file implicit_shape_model.hpp.
float pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::getSamplingSize | ( | ) |
Returns the sampling size used for cloud simplification.
Definition at line 625 of file implicit_shape_model.hpp.
std::vector< float > pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::getSigmaDists | ( | ) |
Returns the array of sigma values.
Definition at line 670 of file implicit_shape_model.hpp.
std::vector< unsigned int > pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::getTrainingClasses | ( | ) |
Returns the array of classes that indicates which class the corresponding training cloud belongs.
Definition at line 592 of file implicit_shape_model.hpp.
std::vector< typename pcl::PointCloud< PointT >::Ptr > pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::getTrainingClouds | ( | ) |
This method simply returns the clouds that were set as the training clouds.
Definition at line 575 of file implicit_shape_model.hpp.
std::vector< typename pcl::PointCloud< NormalT >::Ptr > pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::getTrainingNormals | ( | ) |
This method returns the coresponding cloud of normals for every training point cloud.
Definition at line 608 of file implicit_shape_model.hpp.
ImplicitShapeModelEstimation& pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::operator= | ( | const ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > & | ) | [protected] |
Forbids the assignment operator.
void pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::setFeatureEstimator | ( | boost::shared_ptr< pcl::Feature< PointT, pcl::Histogram< FeatureSize > > > | feature | ) |
Changes the feature estimator.
[in] | feature | feature estimator that will be used to extract the descriptors. Note that it must be fully initialized and configured. |
Definition at line 647 of file implicit_shape_model.hpp.
void pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::setNumberOfClusters | ( | unsigned int | num_of_clusters | ) |
Changes the number of clusters.
num_of_clusters | desired number of clusters |
Definition at line 662 of file implicit_shape_model.hpp.
void pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::setNVotState | ( | bool | state | ) |
Changes the state of the Nvot coeff from [Knopp et al., 2010, (4)].
[in] | state | desired state, if false then Nvot is taken as 1.0 |
Definition at line 693 of file implicit_shape_model.hpp.
void pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::setSamplingSize | ( | float | sampling_size | ) |
Changes the sampling size used for cloud simplification.
[in] | sampling_size | desired size of grid bin |
Definition at line 632 of file implicit_shape_model.hpp.
void pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::setSigmaDists | ( | const std::vector< float > & | training_sigmas | ) |
This method allows to set the value of sigma used for calculating the learned weights for every single class.
[in] | training_sigmas | new sigmas for every class. If you want these values to be computed automatically, just pass the empty array. The automatic regime calculates the maximum distance between the objects points and takes 10% of this value as recomended in the article. If there are several objects of the same class, then it computes the average maximum distance and takes 10%. Note that each class has its own sigma value. |
Definition at line 677 of file implicit_shape_model.hpp.
void pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::setTrainingClasses | ( | const std::vector< unsigned int > & | training_classes | ) |
Allows to set the class labels for the corresponding training clouds.
[in] | training_classes | array of class labels |
Definition at line 599 of file implicit_shape_model.hpp.
void pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::setTrainingClouds | ( | const std::vector< typename pcl::PointCloud< PointT >::Ptr > & | training_clouds | ) |
Allows to set clouds for training the ISM model.
[in] | training_clouds | array of point clouds for training |
Definition at line 582 of file implicit_shape_model.hpp.
void pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::setTrainingNormals | ( | const std::vector< typename pcl::PointCloud< NormalT >::Ptr > & | training_normals | ) |
Allows to set normals for the training clouds that were passed through setTrainingClouds method.
[in] | training_normals | array of clouds, each cloud is the cloud of normals |
Definition at line 615 of file implicit_shape_model.hpp.
void pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::shiftCloud | ( | typename pcl::PointCloud< PointT >::Ptr | in_cloud, |
Eigen::Vector3f | shift_point | ||
) | [protected] |
This method simply shifts the clouds points relative to the passed point.
[in] | in_cloud | cloud to shift |
[in] | shift_point | point relative to which the cloud will be shifted |
Definition at line 1187 of file implicit_shape_model.hpp.
void pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::simplifyCloud | ( | typename pcl::PointCloud< PointT >::ConstPtr | in_point_cloud, |
typename pcl::PointCloud< NormalT >::ConstPtr | in_normal_cloud, | ||
typename pcl::PointCloud< PointT >::Ptr | out_sampled_point_cloud, | ||
typename pcl::PointCloud< NormalT >::Ptr | out_sampled_normal_cloud | ||
) | [protected] |
Simplifies the cloud using voxel grid principles.
[in] | in_point_cloud | cloud that need to be simplified |
[in] | in_normal_cloud | normals of the cloud that need to be simplified |
[out] | out_sampled_point_cloud | simplified cloud |
[out] | out_sampled_normal_cloud | and the corresponding normals |
Definition at line 1123 of file implicit_shape_model.hpp.
bool pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::trainISM | ( | ISMModelPtr & | trained_model | ) |
This method performs training and forms a visual vocabulary. It returns a trained model that can be saved to file for later usage.
[out] | model | trained model |
Definition at line 700 of file implicit_shape_model.hpp.
boost::shared_ptr<pcl::Feature<PointT, pcl::Histogram<FeatureSize> > > pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::feature_estimator_ [protected] |
Stores the feature estimator.
Definition at line 602 of file implicit_shape_model.h.
bool pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::n_vot_ON_ [protected] |
If set to false then Nvot coeff from [Knopp et al., 2010, (4)] is equal 1.0.
Definition at line 608 of file implicit_shape_model.h.
unsigned int pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::number_of_clusters_ [protected] |
Number of clusters, is used for clustering descriptors during the training.
Definition at line 605 of file implicit_shape_model.h.
const int pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::PP_CENTERS = 2 [static, protected] |
This const value is used for indicating that for k-means clustering centers must be generated as described in Arthur, David and Sergei Vassilvitski (2007) k-means++: The Advantages of Careful Seeding.
Definition at line 613 of file implicit_shape_model.h.
float pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::sampling_size_ [protected] |
This value is used for the simplification. It sets the size of grid bin.
Definition at line 599 of file implicit_shape_model.h.
std::vector<unsigned int> pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::training_classes_ [protected] |
Stores the class number for each cloud from training_clouds_.
Definition at line 588 of file implicit_shape_model.h.
std::vector<typename pcl::PointCloud<PointT>::Ptr> pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::training_clouds_ [protected] |
Stores the clouds used for training.
Definition at line 585 of file implicit_shape_model.h.
std::vector<typename pcl::PointCloud<NormalT>::Ptr> pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::training_normals_ [protected] |
Stores the normals for each training cloud.
Definition at line 591 of file implicit_shape_model.h.
std::vector<float> pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::training_sigmas_ [protected] |
This array stores the sigma values for each training class. If this array has a size equals 0, then sigma values will be calculated automatically.
Definition at line 596 of file implicit_shape_model.h.
const int pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT >::USE_INITIAL_LABELS = 1 [static, protected] |
This const value is used for indicating that input labels must be taken as the initial approximation for k-means clustering.
Definition at line 617 of file implicit_shape_model.h.