, including all inherited members.
clearShared() | SpinImageTangent | [virtual] |
col_res_ | SpinImageGeneric | [protected] |
compute(const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const geometry_msgs::Point32 * > &interest_pts, std::vector< std::vector< float > > &results) | Descriptor3D | |
compute(const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const std::vector< int > * > &interest_region_indices, std::vector< std::vector< float > > &results) | Descriptor3D | |
computeAndConcatFeatures(const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const geometry_msgs::Point32 * > &interest_pts, std::vector< Descriptor3D * > &descriptors_3d, std::vector< boost::shared_array< const float > > &concatenated_features) | Descriptor3D | [static] |
computeAndConcatFeatures(const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const std::vector< int > * > &interest_region_indices, std::vector< Descriptor3D * > &descriptors_3d, std::vector< boost::shared_array< const float > > &concatenated_features) | Descriptor3D | [static] |
computeNeighborhoodFeature(const sensor_msgs::PointCloud &data, const std::vector< int > &neighbor_indices, const unsigned int interest_sample_idx, std::vector< float > &result) const | SpinImageGeneric | [protected, virtual] |
debug_ | Descriptor3D | |
Descriptor3D() | Descriptor3D | |
display(const std::vector< float > &spin_image) const | SpinImageGeneric | [protected] |
doComputation(const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const geometry_msgs::Point32 * > &interest_pts, std::vector< std::vector< float > > &results) | NeighborhoodFeature | [protected, virtual] |
doComputation(const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const std::vector< int > * > &interest_region_indices, std::vector< std::vector< float > > &results) | NeighborhoodFeature | [protected, virtual] |
getName() const | SpinImageTangent | [virtual] |
getResultSize() const | Descriptor3D | [inline] |
nbr_cols_ | SpinImageGeneric | [protected] |
nbr_rows_ | SpinImageGeneric | [protected] |
neighborhood_radius_ | NeighborhoodFeature | [protected] |
neighborhood_radius_defined_ | NeighborhoodFeature | [protected] |
NeighborhoodFeature() | NeighborhoodFeature | |
precompute(const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const geometry_msgs::Point32 * > &interest_pts) | SpinImageTangent | [protected, virtual] |
precompute(const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const std::vector< int > * > &interest_region_indices) | SpinImageTangent | [protected, virtual] |
result_size_ | Descriptor3D | [protected] |
result_size_defined_ | Descriptor3D | [protected] |
row_res_ | SpinImageGeneric | [protected] |
spectral_information_ | SpinImageTangent | [private] |
spin_axes_ | SpinImageGeneric | [protected] |
spin_image_centers_ | SpinImageGeneric | [protected] |
SpinImageGeneric() | SpinImageGeneric | |
SpinImageTangent(const double row_res, const double col_res, const unsigned int nbr_rows, const unsigned int nbr_cols, const bool use_interest_regions_only, SpectralAnalysis &spectral_information) | SpinImageTangent | |
~Descriptor3D()=0 | Descriptor3D | [pure virtual] |
~NeighborhoodFeature()=0 | NeighborhoodFeature | [pure virtual] |
~SpinImageGeneric()=0 | SpinImageGeneric | [pure virtual] |