, including all inherited members.
| alignYCoordWithNormal(const NormalT &in_normal) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| applyTransform(Eigen::Vector3f &io_vec, const Eigen::Matrix3f &in_transform) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| calculateSigmas(std::vector< float > &sigmas) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| 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) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| clusterDescriptors(std::vector< pcl::Histogram< FeatureSize > > &histograms, Eigen::MatrixXi &labels, Eigen::MatrixXf &clusters_centers) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| computeDistance(Eigen::VectorXf &vec_1, Eigen::VectorXf &vec_2) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| 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) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| 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) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| extractDescriptors(std::vector< pcl::Histogram< FeatureSize > > &histograms, std::vector< LocationInfo, Eigen::aligned_allocator< LocationInfo > > &locations) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| feature_estimator_ | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| findObjects(ISMModelPtr model, typename pcl::PointCloud< PointT >::Ptr in_cloud, typename pcl::PointCloud< Normal >::Ptr in_normals, int in_class_of_interest) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | |
| generateCentersPP(const Eigen::MatrixXf &data, Eigen::MatrixXf &out_centers, int number_of_clusters, int trials) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| generateRandomCenter(const std::vector< Eigen::Vector2f > &boxes, Eigen::VectorXf ¢er) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| getFeatureEstimator() | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | |
| getNumberOfClusters() | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | |
| getNVotState() | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | |
| getSamplingSize() | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | |
| getSigmaDists() | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | |
| getTrainingClasses() | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | |
| getTrainingClouds() | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | |
| getTrainingNormals() | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | |
| ImplicitShapeModelEstimation() | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | |
| ISMModelPtr typedef | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | |
| n_vot_ON_ | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| number_of_clusters_ | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| operator=(const ImplicitShapeModelEstimation &) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| PP_CENTERS | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected, static] |
| sampling_size_ | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| setFeatureEstimator(boost::shared_ptr< pcl::Feature< PointT, pcl::Histogram< FeatureSize > > > feature) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | |
| setNumberOfClusters(unsigned int num_of_clusters) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | |
| setNVotState(bool state) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | |
| setSamplingSize(float sampling_size) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | |
| setSigmaDists(const std::vector< float > &training_sigmas) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | |
| setTrainingClasses(const std::vector< unsigned int > &training_classes) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | |
| setTrainingClouds(const std::vector< typename pcl::PointCloud< PointT >::Ptr > &training_clouds) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | |
| setTrainingNormals(const std::vector< typename pcl::PointCloud< NormalT >::Ptr > &training_normals) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | |
| shiftCloud(typename pcl::PointCloud< PointT >::Ptr in_cloud, Eigen::Vector3f shift_point) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| 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) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| TermCriteria typedef | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| training_classes_ | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| training_clouds_ | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| training_normals_ | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| training_sigmas_ | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected] |
| trainISM(ISMModelPtr &trained_model) | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | |
| USE_INITIAL_LABELS | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [protected, static] |
| ~ImplicitShapeModelEstimation() | pcl::ism::ImplicitShapeModelEstimation< FeatureSize, PointT, NormalT > | [virtual] |