Public Types | Public Member Functions | Private Member Functions | Private Attributes
pcl::StatisticalMultiscaleInterestRegionExtraction< PointT > Class Template Reference

Class for extracting interest regions from unstructured point clouds, based on a multi scale statistical approach. Please refer to the following publications for more details: Ranjith Unnikrishnan and Martial Hebert Multi-Scale Interest Regions from Unorganized Point Clouds Workshop on Search in 3D (S3D), IEEE Conf. on Computer Vision and Pattern Recognition (CVPR) June, 2008. More...

#include <statistical_multiscale_interest_region_extraction.h>

Inheritance diagram for pcl::StatisticalMultiscaleInterestRegionExtraction< PointT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const
StatisticalMultiscaleInterestRegionExtraction
< PointT > > 
ConstPtr
typedef boost::shared_ptr
< std::vector< int > > 
IndicesPtr
typedef boost::shared_ptr
< StatisticalMultiscaleInterestRegionExtraction
< PointT > > 
Ptr

Public Member Functions

void computeRegionsOfInterest (std::list< IndicesPtr > &rois)
 The method to be called in order to run the algorithm and produce the resulting set of regions of interest.
void generateCloudGraph ()
 Method that generates the underlying nearest neighbor graph based on the input point cloud.
std::vector< float > getScalesVector ()
 Method for getting the scale parameters vector.
void setScalesVector (std::vector< float > &scale_values)
 Method for setting the scale parameters for the algorithm.
 StatisticalMultiscaleInterestRegionExtraction ()
 Empty constructor.

Private Member Functions

void computeF ()
void extractExtrema (std::list< IndicesPtr > &rois)
void geodesicFixedRadiusSearch (size_t &query_index, float &radius, std::vector< int > &result_indices)
bool initCompute ()
 Checks if all the necessary input was given and the computations can successfully start.

Private Attributes

std::vector< std::vector< float > > F_scales_
std::vector< std::vector< float > > geodesic_distances_
std::vector< float > scale_values_

Detailed Description

template<typename PointT>
class pcl::StatisticalMultiscaleInterestRegionExtraction< PointT >

Class for extracting interest regions from unstructured point clouds, based on a multi scale statistical approach. Please refer to the following publications for more details: Ranjith Unnikrishnan and Martial Hebert Multi-Scale Interest Regions from Unorganized Point Clouds Workshop on Search in 3D (S3D), IEEE Conf. on Computer Vision and Pattern Recognition (CVPR) June, 2008.

Statistical Approaches to Multi-scale Point Cloud Processing Ranjith Unnikrishnan PhD Thesis The Robotics Institute Carnegie Mellon University May, 2008

Author:
Alexandru-Eugen Ichim

Definition at line 65 of file statistical_multiscale_interest_region_extraction.h.


Member Typedef Documentation

template<typename PointT>
typedef boost::shared_ptr<std::vector<int> > pcl::StatisticalMultiscaleInterestRegionExtraction< PointT >::IndicesPtr

Constructor & Destructor Documentation

Empty constructor.

Definition at line 74 of file statistical_multiscale_interest_region_extraction.h.


Member Function Documentation

template<typename PointT >
void pcl::StatisticalMultiscaleInterestRegionExtraction< PointT >::computeF ( ) [private]
template<typename PointT >
void pcl::StatisticalMultiscaleInterestRegionExtraction< PointT >::computeRegionsOfInterest ( std::list< IndicesPtr > &  rois)

The method to be called in order to run the algorithm and produce the resulting set of regions of interest.

Definition at line 122 of file statistical_multiscale_interest_region_extraction.hpp.

template<typename PointT >
void pcl::StatisticalMultiscaleInterestRegionExtraction< PointT >::extractExtrema ( std::list< IndicesPtr > &  rois) [private]

Method that generates the underlying nearest neighbor graph based on the input point cloud.

Definition at line 53 of file statistical_multiscale_interest_region_extraction.hpp.

template<typename PointT >
void pcl::StatisticalMultiscaleInterestRegionExtraction< PointT >::geodesicFixedRadiusSearch ( size_t &  query_index,
float &  radius,
std::vector< int > &  result_indices 
) [private]
template<typename PointT>
std::vector<float> pcl::StatisticalMultiscaleInterestRegionExtraction< PointT >::getScalesVector ( ) [inline]

Method for getting the scale parameters vector.

Definition at line 98 of file statistical_multiscale_interest_region_extraction.h.

template<typename PointT >
bool pcl::StatisticalMultiscaleInterestRegionExtraction< PointT >::initCompute ( ) [private]

Checks if all the necessary input was given and the computations can successfully start.

Reimplemented from pcl::PCLBase< PointT >.

Definition at line 91 of file statistical_multiscale_interest_region_extraction.hpp.

template<typename PointT>
void pcl::StatisticalMultiscaleInterestRegionExtraction< PointT >::setScalesVector ( std::vector< float > &  scale_values) [inline]

Method for setting the scale parameters for the algorithm.

Parameters:
scale_valuesvector of scales to determine the size of each scaling step

Definition at line 94 of file statistical_multiscale_interest_region_extraction.h.


Member Data Documentation

template<typename PointT>
std::vector<std::vector<float> > pcl::StatisticalMultiscaleInterestRegionExtraction< PointT >::F_scales_ [private]
template<typename PointT>
std::vector<std::vector<float> > pcl::StatisticalMultiscaleInterestRegionExtraction< PointT >::geodesic_distances_ [private]
template<typename PointT>
std::vector<float> pcl::StatisticalMultiscaleInterestRegionExtraction< PointT >::scale_values_ [private]

The documentation for this class was generated from the following files:


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:43:35