Public Member Functions | Protected Member Functions | Protected Attributes
pcl::features::ISMVoteList< PointT > Class Template Reference

This class is used for storing, analyzing and manipulating votes obtained from ISM algorithm. More...

#include <implicit_shape_model.h>

List of all members.

Public Member Functions

void addVote (pcl::InterestPoint &in_vote, const PointT &vote_origin, int in_class)
 This method simply adds another vote to the list.
void findStrongestPeaks (std::vector< ISMPeak, Eigen::aligned_allocator< ISMPeak > > &out_peaks, int in_class_id, double in_non_maxima_radius, double in_sigma)
 This method finds the strongest peaks (points were density has most higher values). It is based on the non maxima supression principles.
pcl::PointCloud
< pcl::PointXYZRGB >::Ptr 
getColoredCloud (typename pcl::PointCloud< PointT >::Ptr cloud=0)
 Returns the colored cloud that consists of votes for center (blue points) and initial point cloud (if it was passed).
double getDensityAtPoint (const PointT &point, double sigma_dist)
 Returns the density at the specified point.
unsigned int getNumberOfVotes ()
 This method simply returns the number of votes.
 ISMVoteList ()
 Empty constructor with member variables initialization.
virtual ~ISMVoteList ()
 virtual descriptor.

Protected Member Functions

Eigen::Vector3f shiftMean (const Eigen::Vector3f &snapPt, const double in_dSigmaDist)
void validateTree ()
 this method is simply setting up the search tree.

Protected Attributes

std::vector< int > k_ind_
 Stores neighbours indices.
std::vector< float > k_sqr_dist_
 Stores square distances to the corresponding neighbours.
pcl::KdTreeFLANN
< pcl::InterestPoint >::Ptr 
tree_
 Stores the search tree.
bool tree_is_valid_
 Signalizes if the tree is valid.
pcl::PointCloud
< pcl::InterestPoint >::Ptr 
votes_
 Stores all votes.
std::vector< int > votes_class_
 Stores classes for which every single vote was cast.
pcl::PointCloud< PointT >::Ptr votes_origins_
 Stores the origins of the votes.

Detailed Description

template<typename PointT>
class pcl::features::ISMVoteList< PointT >

This class is used for storing, analyzing and manipulating votes obtained from ISM algorithm.

Definition at line 77 of file implicit_shape_model.h.


Constructor & Destructor Documentation

template<typename PointT >
pcl::features::ISMVoteList< PointT >::ISMVoteList ( )

Empty constructor with member variables initialization.

Definition at line 48 of file implicit_shape_model.hpp.

template<typename PointT >
pcl::features::ISMVoteList< PointT >::~ISMVoteList ( ) [virtual]

virtual descriptor.

Definition at line 61 of file implicit_shape_model.hpp.


Member Function Documentation

template<typename PointT >
void pcl::features::ISMVoteList< PointT >::addVote ( pcl::InterestPoint in_vote,
const PointT vote_origin,
int  in_class 
)

This method simply adds another vote to the list.

Parameters:
[in]in_votevote to add
[in]vote_originorigin of the added vote
[in]in_classclass for which this vote is cast

Definition at line 73 of file implicit_shape_model.hpp.

template<typename PointT >
void pcl::features::ISMVoteList< PointT >::findStrongestPeaks ( std::vector< ISMPeak, Eigen::aligned_allocator< ISMPeak > > &  out_peaks,
int  in_class_id,
double  in_non_maxima_radius,
double  in_sigma 
)

This method finds the strongest peaks (points were density has most higher values). It is based on the non maxima supression principles.

Parameters:
[out]out_peaksit will contain the strongest peaks
[in]in_class_idclass of interest for which peaks are evaluated
[in]in_non_maxima_radiusnon maxima supression radius. The shapes radius is recommended for this value.

Definition at line 124 of file implicit_shape_model.hpp.

template<typename PointT >
pcl::PointCloud< pcl::PointXYZRGB >::Ptr pcl::features::ISMVoteList< PointT >::getColoredCloud ( typename pcl::PointCloud< PointT >::Ptr  cloud = 0)

Returns the colored cloud that consists of votes for center (blue points) and initial point cloud (if it was passed).

Parameters:
[in]cloudcloud that needs to be merged with votes for visualizing.

Definition at line 85 of file implicit_shape_model.hpp.

template<typename PointT >
double pcl::features::ISMVoteList< PointT >::getDensityAtPoint ( const PointT point,
double  sigma_dist 
)

Returns the density at the specified point.

Parameters:
[in]pointpoint of interest
[in]sigma_dist

Definition at line 268 of file implicit_shape_model.hpp.

template<typename PointT >
unsigned int pcl::features::ISMVoteList< PointT >::getNumberOfVotes ( )

This method simply returns the number of votes.

Definition at line 293 of file implicit_shape_model.hpp.

template<typename PointT >
Eigen::Vector3f pcl::features::ISMVoteList< PointT >::shiftMean ( const Eigen::Vector3f &  snapPt,
const double  in_dSigmaDist 
) [protected]

Definition at line 241 of file implicit_shape_model.hpp.

template<typename PointT >
void pcl::features::ISMVoteList< PointT >::validateTree ( ) [protected]

this method is simply setting up the search tree.

Definition at line 226 of file implicit_shape_model.hpp.


Member Data Documentation

template<typename PointT >
std::vector<int> pcl::features::ISMVoteList< PointT >::k_ind_ [protected]

Stores neighbours indices.

Definition at line 149 of file implicit_shape_model.h.

template<typename PointT >
std::vector<float> pcl::features::ISMVoteList< PointT >::k_sqr_dist_ [protected]

Stores square distances to the corresponding neighbours.

Definition at line 152 of file implicit_shape_model.h.

template<typename PointT >
pcl::KdTreeFLANN<pcl::InterestPoint>::Ptr pcl::features::ISMVoteList< PointT >::tree_ [protected]

Stores the search tree.

Definition at line 146 of file implicit_shape_model.h.

template<typename PointT >
bool pcl::features::ISMVoteList< PointT >::tree_is_valid_ [protected]

Signalizes if the tree is valid.

Definition at line 137 of file implicit_shape_model.h.

template<typename PointT >
pcl::PointCloud<pcl::InterestPoint>::Ptr pcl::features::ISMVoteList< PointT >::votes_ [protected]

Stores all votes.

Definition at line 134 of file implicit_shape_model.h.

template<typename PointT >
std::vector<int> pcl::features::ISMVoteList< PointT >::votes_class_ [protected]

Stores classes for which every single vote was cast.

Definition at line 143 of file implicit_shape_model.h.

template<typename PointT >
pcl::PointCloud<PointT>::Ptr pcl::features::ISMVoteList< PointT >::votes_origins_ [protected]

Stores the origins of the votes.

Definition at line 140 of file implicit_shape_model.h.


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


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