, including all inherited members.
axis_ratio_ | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [private] |
BaseClass typedef | pcl::Feature< PointInT, PointOutT > | |
centroids_dominant_orientations_ | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [protected] |
cluster_tolerance_ | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [private] |
clusters_ | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [protected] |
compute(PointCloudOut &output) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | |
computeFeature(PointCloudOut &output) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [private, virtual] |
computeRFAndShapeDistribution(PointInTPtr &processed, PointCloudOut &output, std::vector< pcl::PointIndices > &cluster_indices) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | |
ConstPtr typedef | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | |
createTransFromAxes(Eigen::Vector3f &evx, Eigen::Vector3f &evy, Eigen::Vector3f &evz, Eigen::Affine3f &transformPC, Eigen::Matrix4f ¢er_mat) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [inline] |
curv_threshold_ | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [private] |
deinitCompute() | pcl::Feature< PointInT, PointOutT > | [protected, virtual] |
dominant_normals_ | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [protected] |
eps_angle_threshold_ | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [private] |
extractEuclideanClustersSmooth(const pcl::PointCloud< pcl::PointNormal > &cloud, const pcl::PointCloud< pcl::PointNormal > &normals, float tolerance, const pcl::search::Search< pcl::PointNormal >::Ptr &tree, std::vector< pcl::PointIndices > &clusters, double eps_angle, unsigned int min_pts_per_cluster=1, unsigned int max_pts_per_cluster=(std::numeric_limits< int >::max)()) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [private] |
fake_indices_ | pcl::PCLBase< PointInT > | [protected] |
fake_surface_ | pcl::Feature< PointInT, PointOutT > | [protected] |
Feature() | pcl::Feature< PointInT, PointOutT > | [inline] |
feature_name_ | pcl::Feature< PointInT, PointOutT > | [protected] |
FeatureFromNormals() | pcl::FeatureFromNormals< PointInT, PointNT, PointOutT > | [inline] |
filterNormalsWithHighCurvature(const pcl::PointCloud< PointNT > &cloud, std::vector< int > &indices_to_use, std::vector< int > &indices_out, std::vector< int > &indices_in, float threshold) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | |
getCentroidClusters(std::vector< Eigen::Vector3f > ¢roids) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [inline] |
getCentroidNormalClusters(std::vector< Eigen::Vector3f > ¢roids) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [inline] |
getClassName() const | pcl::Feature< PointInT, PointOutT > | [inline, protected] |
getClusterIndices(std::vector< pcl::PointIndices > &indices) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [inline] |
getIndices() | pcl::PCLBase< PointInT > | [inline] |
getInputCloud() | pcl::PCLBase< PointInT > | [inline] |
getInputNormals() const | pcl::FeatureFromNormals< PointInT, PointNT, PointOutT > | [inline] |
getKSearch() const | pcl::Feature< PointInT, PointOutT > | [inline] |
getRadiusSearch() const | pcl::Feature< PointInT, PointOutT > | [inline] |
getSearchMethod() const | pcl::Feature< PointInT, PointOutT > | [inline] |
getSearchParameter() const | pcl::Feature< PointInT, PointOutT > | [inline] |
getSearchSurface() const | pcl::Feature< PointInT, PointOutT > | [inline] |
getTransforms(std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f > > &trans) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [inline] |
getValidTransformsVec(std::vector< bool > &valid) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [inline] |
getViewPoint(float &vpx, float &vpy, float &vpz) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [inline] |
indices_ | pcl::PCLBase< PointInT > | [protected] |
initCompute() | pcl::FeatureFromNormals< PointInT, PointNT, PointOutT > | [protected, virtual] |
input_ | pcl::PCLBase< PointInT > | [protected] |
k_ | pcl::Feature< PointInT, PointOutT > | [protected] |
KdTree typedef | pcl::Feature< PointInT, PointOutT > | |
KdTreePtr typedef | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | |
leaf_size_ | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [private] |
min_axis_value_ | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [private] |
min_points_ | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [private] |
normalize_bins_ | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [private] |
normals_ | pcl::FeatureFromNormals< PointInT, PointNT, PointOutT > | [protected] |
operator[](size_t pos) | pcl::PCLBase< PointInT > | [inline] |
OURCVFHEstimation() | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [inline] |
PCLBase() | pcl::PCLBase< PointInT > | |
PCLBase(const PCLBase &base) | pcl::PCLBase< PointInT > | |
PointCloud typedef | pcl::PCLBase< PointInT > | |
PointCloudConstPtr typedef | pcl::PCLBase< PointInT > | |
PointCloudN typedef | pcl::FeatureFromNormals< PointInT, PointNT, PointOutT > | |
PointCloudNConstPtr typedef | pcl::FeatureFromNormals< PointInT, PointNT, PointOutT > | |
PointCloudNPtr typedef | pcl::FeatureFromNormals< PointInT, PointNT, PointOutT > | |
PointCloudOut typedef | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | |
PointCloudPtr typedef | pcl::PCLBase< PointInT > | |
PointIndicesConstPtr typedef | pcl::PCLBase< PointInT > | |
PointIndicesPtr typedef | pcl::PCLBase< PointInT > | |
PointInTPtr typedef | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | |
Ptr typedef | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | |
radius_normals_ | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [private] |
refine_clusters_ | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [private] |
search_method_surface_ | pcl::Feature< PointInT, PointOutT > | [protected] |
search_parameter_ | pcl::Feature< PointInT, PointOutT > | [protected] |
search_radius_ | pcl::Feature< PointInT, PointOutT > | [protected] |
searchForNeighbors(size_t index, double parameter, std::vector< int > &indices, std::vector< float > &distances) const | pcl::Feature< PointInT, PointOutT > | [inline, protected] |
searchForNeighbors(const PointCloudIn &cloud, size_t index, double parameter, std::vector< int > &indices, std::vector< float > &distances) const | pcl::Feature< PointInT, PointOutT > | [inline, protected] |
SearchMethod typedef | pcl::Feature< PointInT, PointOutT > | |
SearchMethodSurface typedef | pcl::Feature< PointInT, PointOutT > | |
setAxisRatio(float f) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [inline] |
setClusterTolerance(float d) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [inline] |
setCurvatureThreshold(float d) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [inline] |
setEPSAngleThreshold(float d) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [inline] |
setIndices(const IndicesPtr &indices) | pcl::PCLBase< PointInT > | [virtual] |
setIndices(const IndicesConstPtr &indices) | pcl::PCLBase< PointInT > | [virtual] |
setIndices(const PointIndicesConstPtr &indices) | pcl::PCLBase< PointInT > | [virtual] |
setIndices(size_t row_start, size_t col_start, size_t nb_rows, size_t nb_cols) | pcl::PCLBase< PointInT > | [virtual] |
setInputCloud(const PointCloudConstPtr &cloud) | pcl::PCLBase< PointInT > | [virtual] |
setInputNormals(const PointCloudNConstPtr &normals) | pcl::FeatureFromNormals< PointInT, PointNT, PointOutT > | [inline] |
setKSearch(int k) | pcl::Feature< PointInT, PointOutT > | [inline] |
setMinAxisValue(float f) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [inline] |
setMinPoints(size_t min) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [inline] |
setNormalizeBins(bool normalize) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [inline] |
setRadiusNormals(float radius_normals) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [inline] |
setRadiusSearch(double radius) | pcl::Feature< PointInT, PointOutT > | [inline] |
setRefineClusters(float rc) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [inline] |
setSearchMethod(const KdTreePtr &tree) | pcl::Feature< PointInT, PointOutT > | [inline] |
setSearchSurface(const PointCloudInConstPtr &cloud) | pcl::Feature< PointInT, PointOutT > | [inline] |
setViewPoint(float vpx, float vpy, float vpz) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [inline] |
sgurf(Eigen::Vector3f ¢roid, Eigen::Vector3f &normal_centroid, PointInTPtr &processed, std::vector< Eigen::Matrix4f, Eigen::aligned_allocator< Eigen::Matrix4f > > &transformations, PointInTPtr &grid, pcl::PointIndices &indices) | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | |
surface_ | pcl::Feature< PointInT, PointOutT > | [protected] |
transforms_ | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [private] |
tree_ | pcl::Feature< PointInT, PointOutT > | [protected] |
use_indices_ | pcl::PCLBase< PointInT > | [protected] |
valid_transforms_ | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [private] |
vpx_ | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [private] |
vpy_ | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [private] |
vpz_ | pcl::OURCVFHEstimation< PointInT, PointNT, PointOutT > | [private] |
~Feature() | pcl::Feature< PointInT, PointOutT > | [inline, virtual] |
~FeatureFromNormals() | pcl::FeatureFromNormals< PointInT, PointNT, PointOutT > | [inline, virtual] |
~PCLBase() | pcl::PCLBase< PointInT > | [inline, virtual] |