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

KLDAdaptiveParticleFilterOMPTracker 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]. and the computation of the weights of the particles is parallelized using OpenMP. More...

#include <kld_adaptive_particle_filter_omp.h>

Inheritance diagram for pcl::tracking::KLDAdaptiveParticleFilterOMPTracker< 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

 KLDAdaptiveParticleFilterOMPTracker (unsigned int nr_threads=0)
 Initialize the scheduler and set the number of threads to use.
void setNumberOfThreads (unsigned int nr_threads=0)
 Initialize the scheduler and set the number of threads to use.

Protected Member Functions

virtual void weight ()
 weighting phase of particle filter method. calculate the likelihood of all of the particles and set the weights.

Protected Attributes

unsigned int threads_
 The number of threads the scheduler should use.

Detailed Description

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

KLDAdaptiveParticleFilterOMPTracker 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]. and the computation of the weights of the particles is parallelized using OpenMP.

Author:
Ryohei Ueda

Definition at line 20 of file kld_adaptive_particle_filter_omp.h.


Member Typedef Documentation

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

Constructor & Destructor Documentation

template<typename PointInT , typename StateT >
pcl::tracking::KLDAdaptiveParticleFilterOMPTracker< PointInT, StateT >::KLDAdaptiveParticleFilterOMPTracker ( unsigned int  nr_threads = 0) [inline]

Initialize the scheduler and set the number of threads to use.

Parameters:
nr_threadsthe number of hardware threads to use (0 sets the value back to automatic)

Definition at line 69 of file kld_adaptive_particle_filter_omp.h.


Member Function Documentation

template<typename PointInT , typename StateT >
void pcl::tracking::KLDAdaptiveParticleFilterOMPTracker< PointInT, StateT >::setNumberOfThreads ( unsigned int  nr_threads = 0) [inline]

Initialize the scheduler and set the number of threads to use.

Parameters:
nr_threadsthe number of hardware threads to use (0 sets the value back to automatic)

Definition at line 80 of file kld_adaptive_particle_filter_omp.h.

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

weighting phase of particle filter method. calculate the likelihood of all of the particles and set the weights.

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

Definition at line 7 of file kld_adaptive_particle_filter_omp.hpp.


Member Data Documentation

template<typename PointInT , typename StateT >
unsigned int pcl::tracking::KLDAdaptiveParticleFilterOMPTracker< PointInT, StateT >::threads_ [protected]

The number of threads the scheduler should use.

Definition at line 84 of file kld_adaptive_particle_filter_omp.h.


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


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:47:16