Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT > Class Template Reference

KLDAdaptiveParticleFilterTracker tracks the PointCloud which is given by setReferenceCloud within the measured PointCloud using particle filter method. The number of the particles changes adaptively based on KLD sampling [D. Fox, NIPS-01], [D.Fox, IJRR03]. More...

#include <kld_adaptive_particle_filter.h>

Inheritance diagram for pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef Tracker< PointInT, StateT > BaseClass
typedef PointCloudCoherence
< PointInT > 
CloudCoherence
typedef boost::shared_ptr
< const CloudCoherence
CloudCoherenceConstPtr
typedef boost::shared_ptr
< CloudCoherence
CloudCoherencePtr
typedef PointCoherence< PointInT > Coherence
typedef boost::shared_ptr
< const Coherence
CoherenceConstPtr
typedef boost::shared_ptr
< Coherence
CoherencePtr
typedef Tracker< PointInT,
StateT >::PointCloudIn 
PointCloudIn
typedef PointCloudIn::ConstPtr PointCloudInConstPtr
typedef PointCloudIn::Ptr PointCloudInPtr
typedef Tracker< PointInT,
StateT >::PointCloudState 
PointCloudState
typedef PointCloudState::ConstPtr PointCloudStateConstPtr
typedef PointCloudState::Ptr PointCloudStatePtr

Public Member Functions

StateT getBinSize () const
 get the bin size.
double getDelta () const
 get delta to be used in chi-squared distribution.
double getEpsilon () const
 get epsilon to be used to calc K-L boundary.
unsigned int getMaximumParticleNum () const
 get the maximum number of the particles.
 KLDAdaptiveParticleFilterTracker ()
 Empty constructor.
void setBinSize (const StateT &bin_size)
 set the bin size.
void setDelta (double delta)
 set delta to be used in chi-squared distribution.
void setEpsilon (double eps)
 set epsilon to be used to calc K-L boundary.
void setMaximumParticleNum (unsigned int nr)
 set the maximum number of the particles.

Protected Member Functions

virtual double calcKLBound (int k)
 calculate K-L boundary. K-L boundary follows 1/2e*chi(k-1, 1-d)^2.
virtual bool equalBin (std::vector< int > a, std::vector< int > b)
 return true if the two bins are equal.
virtual bool initCompute ()
 This method should get called before starting the actual computation.
virtual bool insertIntoBins (std::vector< int > bin, std::vector< std::vector< int > > &B)
 insert a bin into the set of the bins. if that bin is already registered, return false. if not, return true.
double normalQuantile (double u)
 return upper quantile of standard normal distribution.
virtual void resample ()
 resampling phase of particle filter method. sampling the particles according to the weights calculated in weight method. in particular, "sample with replacement" is archieved by walker's alias method.

Protected Attributes

StateT bin_size_
 the size of a bin.
double delta_
 probability of distance between K-L distance and MLE is less than epsilon_
double epsilon_
 error between K-L distance and MLE
unsigned int maximum_particle_number_
 the maximum number of the particles.

Detailed Description

template<typename PointInT, typename StateT>
class pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >

KLDAdaptiveParticleFilterTracker tracks the PointCloud which is given by setReferenceCloud within the measured PointCloud using particle filter method. The number of the particles changes adaptively based on KLD sampling [D. Fox, NIPS-01], [D.Fox, IJRR03].

Author:
Ryohei Ueda

Definition at line 20 of file kld_adaptive_particle_filter.h.


Member Typedef Documentation

template<typename PointInT , typename StateT >
typedef Tracker<PointInT, StateT> pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::BaseClass
template<typename PointInT , typename StateT >
typedef PointCloudCoherence<PointInT> pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::CloudCoherence
template<typename PointInT , typename StateT >
typedef boost::shared_ptr< const CloudCoherence > pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::CloudCoherenceConstPtr
template<typename PointInT , typename StateT >
typedef boost::shared_ptr< CloudCoherence > pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::CloudCoherencePtr
template<typename PointInT , typename StateT >
typedef PointCoherence<PointInT> pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::Coherence
template<typename PointInT , typename StateT >
typedef boost::shared_ptr< const Coherence > pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::CoherenceConstPtr
template<typename PointInT , typename StateT >
typedef boost::shared_ptr< Coherence > pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::CoherencePtr
template<typename PointInT , typename StateT >
typedef Tracker<PointInT, StateT>::PointCloudIn pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::PointCloudIn
template<typename PointInT , typename StateT >
typedef PointCloudIn::ConstPtr pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::PointCloudInConstPtr
template<typename PointInT , typename StateT >
typedef PointCloudIn::Ptr pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::PointCloudInPtr
template<typename PointInT , typename StateT >
typedef Tracker<PointInT, StateT>::PointCloudState pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::PointCloudState
template<typename PointInT , typename StateT >
typedef PointCloudState::ConstPtr pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::PointCloudStateConstPtr
template<typename PointInT , typename StateT >
typedef PointCloudState::Ptr pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::PointCloudStatePtr

Constructor & Destructor Documentation

template<typename PointInT , typename StateT >
pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::KLDAdaptiveParticleFilterTracker ( ) [inline]

Empty constructor.

Definition at line 64 of file kld_adaptive_particle_filter.h.


Member Function Documentation

template<typename PointInT , typename StateT >
virtual double pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::calcKLBound ( int  k) [inline, protected, virtual]

calculate K-L boundary. K-L boundary follows 1/2e*chi(k-1, 1-d)^2.

Parameters:
[in]kthe number of bins and the first parameter of chi distribution.

Definition at line 173 of file kld_adaptive_particle_filter.h.

template<typename PointInT , typename StateT >
virtual bool pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::equalBin ( std::vector< int >  a,
std::vector< int >  b 
) [inline, protected, virtual]

return true if the two bins are equal.

Parameters:
aindex of the bin
bindex of the bin

Definition at line 113 of file kld_adaptive_particle_filter.h.

template<typename PointInT , typename StateT >
StateT pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::getBinSize ( ) const [inline]

get the bin size.

Definition at line 80 of file kld_adaptive_particle_filter.h.

template<typename PointInT , typename StateT >
double pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::getDelta ( ) const [inline]

get delta to be used in chi-squared distribution.

Definition at line 104 of file kld_adaptive_particle_filter.h.

template<typename PointInT , typename StateT >
double pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::getEpsilon ( ) const [inline]

get epsilon to be used to calc K-L boundary.

Definition at line 96 of file kld_adaptive_particle_filter.h.

template<typename PointInT , typename StateT >
unsigned int pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::getMaximumParticleNum ( ) const [inline]

get the maximum number of the particles.

Definition at line 88 of file kld_adaptive_particle_filter.h.

template<typename PointInT , typename StateT >
bool pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::initCompute ( ) [protected, virtual]

This method should get called before starting the actual computation.

Reimplemented from pcl::tracking::ParticleFilterTracker< PointInT, StateT >.

Definition at line 5 of file kld_adaptive_particle_filter.hpp.

template<typename PointInT , typename StateT >
bool pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::insertIntoBins ( std::vector< int >  bin,
std::vector< std::vector< int > > &  B 
) [protected, virtual]

insert a bin into the set of the bins. if that bin is already registered, return false. if not, return true.

Parameters:
bina bin to be inserted.
Ba set of the bins

Definition at line 35 of file kld_adaptive_particle_filter.hpp.

template<typename PointInT , typename StateT >
double pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::normalQuantile ( double  u) [inline, protected]

return upper quantile of standard normal distribution.

Parameters:
[in]uratio of quantile.

Definition at line 126 of file kld_adaptive_particle_filter.h.

template<typename PointInT , typename StateT >
void pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::resample ( ) [protected, virtual]

resampling phase of particle filter method. sampling the particles according to the weights calculated in weight method. in particular, "sample with replacement" is archieved by walker's alias method.

Reimplemented from pcl::tracking::ParticleFilterTracker< PointInT, StateT >.

Definition at line 47 of file kld_adaptive_particle_filter.hpp.

template<typename PointInT , typename StateT >
void pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::setBinSize ( const StateT &  bin_size) [inline]

set the bin size.

Parameters:
bin_sizethe size of a bin

Definition at line 77 of file kld_adaptive_particle_filter.h.

template<typename PointInT , typename StateT >
void pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::setDelta ( double  delta) [inline]

set delta to be used in chi-squared distribution.

Parameters:
deltadelta of chi-squared distribution.

Definition at line 101 of file kld_adaptive_particle_filter.h.

template<typename PointInT , typename StateT >
void pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::setEpsilon ( double  eps) [inline]

set epsilon to be used to calc K-L boundary.

Parameters:
epsepsilon

Definition at line 93 of file kld_adaptive_particle_filter.h.

template<typename PointInT , typename StateT >
void pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::setMaximumParticleNum ( unsigned int  nr) [inline]

set the maximum number of the particles.

Parameters:
nrthe maximum number of the particles.

Definition at line 85 of file kld_adaptive_particle_filter.h.


Member Data Documentation

template<typename PointInT , typename StateT >
StateT pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::bin_size_ [protected]

the size of a bin.

Definition at line 209 of file kld_adaptive_particle_filter.h.

template<typename PointInT , typename StateT >
double pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::delta_ [protected]

probability of distance between K-L distance and MLE is less than epsilon_

Definition at line 206 of file kld_adaptive_particle_filter.h.

template<typename PointInT , typename StateT >
double pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::epsilon_ [protected]

error between K-L distance and MLE

Definition at line 203 of file kld_adaptive_particle_filter.h.

template<typename PointInT , typename StateT >
unsigned int pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::maximum_particle_number_ [protected]

the maximum number of the particles.

Definition at line 200 of file kld_adaptive_particle_filter.h.


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


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:20:30