point_cloud_library / 1.12.1 / classpcl_1_1tracking_1_1_k_l_d_adaptive_particle_filter_tracker.html /

KLDAdaptiveParticleFilterTracker tracks the PointCloud which is given by setReferenceCloud within the measured PointCloud using particle filter method. More...

#include <pcl/tracking/kld_adaptive_particle_filter.h>

Public Types

using BaseClass = Tracker< PointInT, StateT >
using Ptr = shared_ptr< KLDAdaptiveParticleFilterTracker< PointInT, StateT > >
using ConstPtr = shared_ptr< const KLDAdaptiveParticleFilterTracker< PointInT, StateT > >
using PointCloudIn = typename Tracker< PointInT, StateT >::PointCloudIn
using PointCloudInPtr = typename PointCloudIn::Ptr
using PointCloudInConstPtr = typename PointCloudIn::ConstPtr
using PointCloudState = typename Tracker< PointInT, StateT >::PointCloudState
using PointCloudStatePtr = typename PointCloudState::Ptr
using PointCloudStateConstPtr = typename PointCloudState::ConstPtr
using Coherence = PointCoherence< PointInT >
using CoherencePtr = typename Coherence::Ptr
using CoherenceConstPtr = typename Coherence::ConstPtr
using CloudCoherence = PointCloudCoherence< PointInT >
using CloudCoherencePtr = typename CloudCoherence::Ptr
using CloudCoherenceConstPtr = typename CloudCoherence::ConstPtr
- Public Types inherited from pcl::tracking::ParticleFilterTracker< PointInT, StateT >
using Ptr = shared_ptr< ParticleFilterTracker< PointInT, StateT > >
using ConstPtr = shared_ptr< const ParticleFilterTracker< PointInT, StateT > >
using BaseClass = Tracker< PointInT, StateT >
using PointCloudIn = typename Tracker< PointInT, StateT >::PointCloudIn
using PointCloudInPtr = typename PointCloudIn::Ptr
using PointCloudInConstPtr = typename PointCloudIn::ConstPtr
using PointCloudState = typename Tracker< PointInT, StateT >::PointCloudState
using PointCloudStatePtr = typename PointCloudState::Ptr
using PointCloudStateConstPtr = typename PointCloudState::ConstPtr
using Coherence = PointCoherence< PointInT >
using CoherencePtr = typename Coherence::Ptr
using CoherenceConstPtr = typename Coherence::ConstPtr
using CloudCoherence = PointCloudCoherence< PointInT >
using CloudCoherencePtr = typename CloudCoherence::Ptr
using CloudCoherenceConstPtr = typename CloudCoherence::ConstPtr
- Public Types inherited from pcl::tracking::Tracker< PointInT, StateT >
using BaseClass = PCLBase< PointInT >
using Ptr = shared_ptr< Tracker< PointInT, StateT > >
using ConstPtr = shared_ptr< const Tracker< PointInT, StateT > >
using SearchPtr = typename pcl::search::Search< PointInT >::Ptr
using SearchConstPtr = typename pcl::search::Search< PointInT >::ConstPtr
using PointCloudIn = pcl::PointCloud< PointInT >
using PointCloudInPtr = typename PointCloudIn::Ptr
using PointCloudInConstPtr = typename PointCloudIn::ConstPtr
using PointCloudState = pcl::PointCloud< StateT >
using PointCloudStatePtr = typename PointCloudState::Ptr
using PointCloudStateConstPtr = typename PointCloudState::ConstPtr
- Public Types inherited from pcl::PCLBase< PointInT >
using PointCloud = pcl::PointCloud< PointInT >
using PointCloudPtr = typename PointCloud::Ptr
using PointCloudConstPtr = typename PointCloud::ConstPtr
using PointIndicesPtr = PointIndices::Ptr
using PointIndicesConstPtr = PointIndices::ConstPtr

Public Member Functions

KLDAdaptiveParticleFilterTracker ()
Empty constructor. More...
void setBinSize (const StateT &bin_size)
set the bin size. More...
StateT getBinSize () const
get the bin size. More...
void setMaximumParticleNum (unsigned int nr)
set the maximum number of the particles. More...
unsigned int getMaximumParticleNum () const
get the maximum number of the particles. More...
void setEpsilon (double eps)
set epsilon to be used to calc K-L boundary. More...
double getEpsilon () const
get epsilon to be used to calc K-L boundary. More...
void setDelta (double delta)
set delta to be used in chi-squared distribution. More...
double getDelta () const
get delta to be used in chi-squared distribution. More...
- Public Member Functions inherited from pcl::tracking::ParticleFilterTracker< PointInT, StateT >
ParticleFilterTracker ()
Empty constructor. More...
void setIterationNum (const int iteration_num)
Set the number of iteration. More...
int getIterationNum () const
Get the number of iteration. More...
void setParticleNum (const int particle_num)
Set the number of the particles. More...
int getParticleNum () const
Get the number of the particles. More...
void setReferenceCloud (const PointCloudInConstPtr &ref)
Set a pointer to a reference dataset to be tracked. More...
const PointCloudInConstPtr getReferenceCloud ()
Get a pointer to a reference dataset to be tracked. More...
void setCloudCoherence (const CloudCoherencePtr &coherence)
Set the PointCloudCoherence as likelihood. More...
CloudCoherencePtr getCloudCoherence () const
Get the PointCloudCoherence to compute likelihood. More...
void setStepNoiseCovariance (const std::vector< double > &step_noise_covariance)
Set the covariance of step noise. More...
void setInitialNoiseCovariance (const std::vector< double > &initial_noise_covariance)
Set the covariance of the initial noise. More...
void setInitialNoiseMean (const std::vector< double > &initial_noise_mean)
Set the mean of the initial noise. More...
void setResampleLikelihoodThr (const double resample_likelihood_thr)
Set the threshold to re-initialize the particles. More...
void setOcclusionAngleThe (const double occlusion_angle_thr)
Set the threshold of angle to be considered occlusion (default: pi/2). More...
void setMinIndices (const int min_indices)
Set the minimum number of indices (default: 1). More...
void setTrans (const Eigen::Affine3f &trans)
Set the transformation from the world coordinates to the frame of the particles. More...
Eigen::Affine3f getTrans () const
Get the transformation from the world coordinates to the frame of the particles. More...
StateT getResult () const override
Get an instance of the result of tracking. More...
Eigen::Affine3f toEigenMatrix (const StateT &particle)
Convert a state to affine transformation from the world coordinates frame. More...
PointCloudStatePtr getParticles () const
Get a pointer to a pointcloud of the particles. More...
double normalizeParticleWeight (double w, double w_min, double w_max)
Normalize the weight of a particle using $ std::exp(1- alpha ( w - w_{min}) / (w_max - w_min)) $. More...
void setAlpha (double alpha)
Set the value of alpha. More...
double getAlpha ()
Get the value of alpha. More...
void setUseNormal (bool use_normal)
Set the value of use_normal_. More...
bool getUseNormal ()
Get the value of use_normal_. More...
void setUseChangeDetector (bool use_change_detector)
Set the value of use_change_detector_. More...
bool getUseChangeDetector ()
Get the value of use_change_detector_. More...
void setMotionRatio (double motion_ratio)
Set the motion ratio. More...
double getMotionRatio ()
Get the motion ratio. More...
void setIntervalOfChangeDetection (unsigned int change_detector_interval)
Set the number of interval frames to run change detection. More...
unsigned int getIntervalOfChangeDetection ()
Get the number of interval frames to run change detection. More...
void setMinPointsOfChangeDetection (unsigned int change_detector_filter)
Set the minimum amount of points required within leaf node to become serialized in change detection. More...
void setResolutionOfChangeDetection (double resolution)
Set the resolution of change detection. More...
double getResolutionOfChangeDetection ()
Get the resolution of change detection. More...
unsigned int getMinPointsOfChangeDetection ()
Get the minimum amount of points required within leaf node to become serialized in change detection. More...
double getFitRatio () const
Get the adjustment ratio. More...
virtual void resetTracking ()
Reset the particles to restart tracking. More...
- Public Member Functions inherited from pcl::tracking::Tracker< PointInT, StateT >
Tracker ()
Empty constructor. More...
void compute ()
Base method for tracking for all points given in <setInputCloud (), setIndices ()> using the indices in setIndices () More...
- Public Member Functions inherited from pcl::PCLBase< PointInT >
PCLBase ()
Empty constructor. More...
PCLBase (const PCLBase &base)
Copy constructor. More...
virtual ~PCLBase ()=default
Destructor. More...
virtual void setInputCloud (const PointCloudConstPtr &cloud)
Provide a pointer to the input dataset. More...
const PointCloudConstPtr getInputCloud () const
Get a pointer to the input point cloud dataset. More...
virtual void setIndices (const IndicesPtr &indices)
Provide a pointer to the vector of indices that represents the input data. More...
virtual void setIndices (const IndicesConstPtr &indices)
Provide a pointer to the vector of indices that represents the input data. More...
virtual void setIndices (const PointIndicesConstPtr &indices)
Provide a pointer to the vector of indices that represents the input data. More...
virtual void setIndices (std::size_t row_start, std::size_t col_start, std::size_t nb_rows, std::size_t nb_cols)
Set the indices for the points laying within an interest region of the point cloud. More...
IndicesPtr getIndices ()
Get a pointer to the vector of indices used. More...
const IndicesConstPtr getIndices () const
Get a pointer to the vector of indices used. More...
const PointInT & operator[] (std::size_t pos) const
Override PointCloud operator[] to shorten code. More...

Protected Member Functions

virtual bool equalBin (const std::vector< int > &a, const std::vector< int > &b)
return true if the two bins are equal. More...
double normalQuantile (double u)
return upper quantile of standard normal distribution. More...
virtual double calcKLBound (int k)
calculate K-L boundary. More...
virtual bool insertIntoBins (std::vector< int > &&new_bin, std::vector< std::vector< int >> &bins)
insert a bin into the set of the bins. More...
bool initCompute () override
This method should get called before starting the actual computation. More...
void resample () override
resampling phase of particle filter method. More...
- Protected Member Functions inherited from pcl::tracking::ParticleFilterTracker< PointInT, StateT >
void calcBoundingBox (double &x_min, double &x_max, double &y_min, double &y_max, double &z_min, double &z_max)
Compute the parameters for the bounding box of hypothesis pointclouds. More...
void cropInputPointCloud (const PointCloudInConstPtr &cloud, PointCloudIn &output)
Crop the pointcloud by the bounding box calculated from hypothesis and the reference pointcloud. More...
void computeTransformedPointCloud (const StateT &hypothesis, pcl::Indices &indices, PointCloudIn &cloud)
Compute a reference pointcloud transformed to the pose that hypothesis represents. More...
void computeTransformedPointCloudWithNormal (const StateT &hypothesis, pcl::Indices &indices, PointCloudIn &cloud)
Compute a reference pointcloud transformed to the pose that hypothesis represents and calculate indices taking occlusion into account. More...
void computeTransformedPointCloudWithoutNormal (const StateT &hypothesis, PointCloudIn &cloud)
Compute a reference pointcloud transformed to the pose that hypothesis represents and calculate indices without taking occlusion into account. More...
bool initCompute () override
This method should get called before starting the actua computation. More...
virtual void weight ()
Weighting phase of particle filter method. More...
virtual void update ()
Calculate the weighted mean of the particles and set it as the result. More...
virtual void normalizeWeight ()
Normalize the weights of all the particels. More...
void initParticles (bool reset)
Initialize the particles. More...
void computeTracking () override
Track the pointcloud using particle filter method. More...
int sampleWithReplacement (const std::vector< int > &a, const std::vector< double > &q)
Implementation of "sample with replacement" using Walker's alias method. More...
void genAliasTable (std::vector< int > &a, std::vector< double > &q, const PointCloudStateConstPtr &particles)
Generate the tables for walker's alias method. More...
void resampleWithReplacement ()
Resampling the particle with replacement. More...
void resampleDeterministic ()
Resampling the particle in deterministic way. More...
bool testChangeDetection (const PointCloudInConstPtr &input)
Run change detection and return true if there is a change. More...
- Protected Member Functions inherited from pcl::tracking::Tracker< PointInT, StateT >
const std::string & getClassName () const
Get a string representation of the name of this class. More...
void setSearchMethod (const SearchPtr &search)
Provide a pointer to a dataset to add additional information to estimate the features for every point in the input dataset. More...
SearchPtr getSearchMethod ()
Get a pointer to the point cloud dataset. More...
- Protected Member Functions inherited from pcl::PCLBase< PointInT >
bool initCompute ()
This method should get called before starting the actual computation. More...
bool deinitCompute ()
This method should get called after finishing the actual computation. More...

Protected Attributes

unsigned int maximum_particle_number_
the maximum number of the particles. More...
double epsilon_
error between K-L distance and MLE More...
double delta_
probability of distance between K-L distance and MLE is less than epsilon_ More...
StateT bin_size_
the size of a bin. More...
- Protected Attributes inherited from pcl::tracking::ParticleFilterTracker< PointInT, StateT >
int iteration_num_
The number of iteration of particlefilter. More...
int particle_num_
The number of the particles. More...
int min_indices_
The minimum number of points which the hypothesis should have. More...
double fit_ratio_
Adjustment of the particle filter. More...
PointCloudInConstPtr ref_
A pointer to reference point cloud. More...
PointCloudStatePtr particles_
A pointer to the particles
More...
CloudCoherencePtr coherence_
A pointer to PointCloudCoherence. More...
std::vector< double > step_noise_covariance_
The diagonal elements of covariance matrix of the step noise. More...
std::vector< double > initial_noise_covariance_
The diagonal elements of covariance matrix of the initial noise. More...
std::vector< double > initial_noise_mean_
The mean values of initial noise. More...
double resample_likelihood_thr_
The threshold for the particles to be re-initialized. More...
double occlusion_angle_thr_
The threshold for the points to be considered as occluded. More...
double alpha_
The weight to be used in normalization of the weights of the particles. More...
StateT representative_state_
The result of tracking. More...
Eigen::Affine3f trans_
An affine transformation from the world coordinates frame to the origin of the particles. More...
bool use_normal_
A flag to use normal or not. More...
StateT motion_
Difference between the result in t and t-1. More...
double motion_ratio_
Ratio of hypothesis to use motion model. More...
pcl::PassThrough< PointInT > pass_x_
Pass through filter to crop the pointclouds within the hypothesis bounding box. More...
pcl::PassThrough< PointInT > pass_y_
Pass through filter to crop the pointclouds within the hypothesis bounding box. More...
pcl::PassThrough< PointInT > pass_z_
Pass through filter to crop the pointclouds within the hypothesis bounding box. More...
std::vector< PointCloudInPtr > transed_reference_vector_
A list of the pointers to pointclouds. More...
pcl::octree::OctreePointCloudChangeDetector< PointInT >::Ptr change_detector_
Change detector used as a trigger to track. More...
bool changed_
A flag to be true when change of pointclouds is detected. More...
unsigned int change_counter_
A counter to skip change detection. More...
unsigned int change_detector_filter_
Minimum points in a leaf when calling change detector. More...
unsigned int change_detector_interval_
The number of interval frame to run change detection. More...
double change_detector_resolution_
Resolution of change detector. More...
bool use_change_detector_
The flag which will be true if using change detection. More...
- Protected Attributes inherited from pcl::tracking::Tracker< PointInT, StateT >
std::string tracker_name_
The tracker name. More...
SearchPtr search_
A pointer to the spatial search object. More...
- Protected Attributes inherited from pcl::PCLBase< PointInT >
PointCloudConstPtr input_
The input point cloud dataset. More...
IndicesPtr indices_
A pointer to the vector of point indices to use. More...
bool use_indices_
Set to true if point indices are used. More...
bool fake_indices_
If no set of indices are given, we construct a set of fake indices that mimic the input PointCloud. More...

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 18 of file kld_adaptive_particle_filter.h.

Member Typedef Documentation

BaseClass

template<typename PointInT , typename StateT >
using pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::BaseClass = Tracker<PointInT, StateT>

Definition at line 43 of file kld_adaptive_particle_filter.h.

CloudCoherence

template<typename PointInT , typename StateT >
using pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::CloudCoherence = PointCloudCoherence<PointInT>

Definition at line 60 of file kld_adaptive_particle_filter.h.

CloudCoherenceConstPtr

template<typename PointInT , typename StateT >
using pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::CloudCoherenceConstPtr = typename CloudCoherence::ConstPtr

Definition at line 62 of file kld_adaptive_particle_filter.h.

CloudCoherencePtr

template<typename PointInT , typename StateT >
using pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::CloudCoherencePtr = typename CloudCoherence::Ptr

Definition at line 61 of file kld_adaptive_particle_filter.h.

Coherence

template<typename PointInT , typename StateT >
using pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::Coherence = PointCoherence<PointInT>

Definition at line 56 of file kld_adaptive_particle_filter.h.

CoherenceConstPtr

template<typename PointInT , typename StateT >
using pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::CoherenceConstPtr = typename Coherence::ConstPtr

Definition at line 58 of file kld_adaptive_particle_filter.h.

CoherencePtr

template<typename PointInT , typename StateT >
using pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::CoherencePtr = typename Coherence::Ptr

Definition at line 57 of file kld_adaptive_particle_filter.h.

ConstPtr

template<typename PointInT , typename StateT >
using pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::ConstPtr = shared_ptr<const KLDAdaptiveParticleFilterTracker<PointInT, StateT> >

Definition at line 46 of file kld_adaptive_particle_filter.h.

PointCloudIn

template<typename PointInT , typename StateT >
using pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::PointCloudIn = typename Tracker<PointInT, StateT>::PointCloudIn

Definition at line 48 of file kld_adaptive_particle_filter.h.

PointCloudInConstPtr

template<typename PointInT , typename StateT >
using pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::PointCloudInConstPtr = typename PointCloudIn::ConstPtr

Definition at line 50 of file kld_adaptive_particle_filter.h.

PointCloudInPtr

template<typename PointInT , typename StateT >
using pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::PointCloudInPtr = typename PointCloudIn::Ptr

Definition at line 49 of file kld_adaptive_particle_filter.h.

PointCloudState

template<typename PointInT , typename StateT >
using pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::PointCloudState = typename Tracker<PointInT, StateT>::PointCloudState

Definition at line 52 of file kld_adaptive_particle_filter.h.

PointCloudStateConstPtr

template<typename PointInT , typename StateT >
using pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::PointCloudStateConstPtr = typename PointCloudState::ConstPtr

Definition at line 54 of file kld_adaptive_particle_filter.h.

PointCloudStatePtr

template<typename PointInT , typename StateT >
using pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::PointCloudStatePtr = typename PointCloudState::Ptr

Definition at line 53 of file kld_adaptive_particle_filter.h.

Ptr

template<typename PointInT , typename StateT >
using pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::Ptr = shared_ptr<KLDAdaptiveParticleFilterTracker<PointInT, StateT> >

Definition at line 45 of file kld_adaptive_particle_filter.h.

Constructor & Destructor Documentation

KLDAdaptiveParticleFilterTracker()

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

Empty constructor.

Definition at line 65 of file kld_adaptive_particle_filter.h.

References pcl::tracking::Tracker< PointInT, StateT >::tracker_name_.

Member Function Documentation

calcKLBound()

template<typename PointInT , typename StateT >
virtual double pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::calcKLBound ( int k )
inlineprotectedvirtual

calculate K-L boundary.

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

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

Definition at line 218 of file kld_adaptive_particle_filter.h.

References pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::delta_, pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::epsilon_, and pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::normalQuantile().

equalBin()

template<typename PointInT , typename StateT >
virtual bool pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::equalBin ( const std::vector< int > & a,
const std::vector< int > & b
)
inlineprotectedvirtual

return true if the two bins are equal.

Parameters
a index of the bin
b index of the bin

Definition at line 145 of file kld_adaptive_particle_filter.h.

getBinSize()

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

getDelta()

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 134 of file kld_adaptive_particle_filter.h.

References pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::delta_.

getEpsilon()

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 118 of file kld_adaptive_particle_filter.h.

References pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::epsilon_.

getMaximumParticleNum()

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 102 of file kld_adaptive_particle_filter.h.

References pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::maximum_particle_number_.

initCompute()

template<typename PointInT , typename StateT >
bool pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::initCompute
overrideprotectedvirtual

This method should get called before starting the actual computation.

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

Definition at line 10 of file kld_adaptive_particle_filter.hpp.

insertIntoBins()

template<typename PointInT , typename StateT >
bool pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::insertIntoBins ( std::vector< int > && new_bin,
std::vector< std::vector< int >> & bins
)
protectedvirtual

insert a bin into the set of the bins.

if that bin is already registered, return false. if not, return true.

Parameters
new_bin a bin to be inserted.
bins a set of the bins

Definition at line 38 of file kld_adaptive_particle_filter.hpp.

normalQuantile()

template<typename PointInT , typename StateT >
double pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::normalQuantile ( double u )
inlineprotected

return upper quantile of standard normal distribution.

Parameters
[in] u ratio of quantile.

Definition at line 158 of file kld_adaptive_particle_filter.h.

Referenced by pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::calcKLBound().

resample()

template<typename PointInT , typename StateT >
void pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::resample
overrideprotectedvirtual

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 51 of file kld_adaptive_particle_filter.hpp.

setBinSize()

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

set the bin size.

Parameters
bin_size the size of a bin

Definition at line 79 of file kld_adaptive_particle_filter.h.

References pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::bin_size_.

setDelta()

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
delta delta of chi-squared distribution.

Definition at line 127 of file kld_adaptive_particle_filter.h.

References pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::delta_.

setEpsilon()

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
eps epsilon

Definition at line 111 of file kld_adaptive_particle_filter.h.

References pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::epsilon_.

setMaximumParticleNum()

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

set the maximum number of the particles.

Parameters
nr the maximum number of the particles.

Definition at line 95 of file kld_adaptive_particle_filter.h.

References pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >::maximum_particle_number_.

Member Data Documentation

bin_size_

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

delta_

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

epsilon_

maximum_particle_number_

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

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

© 2009–2012, Willow Garage, Inc.
© 2012–, Open Perception, Inc.
Licensed under the BSD License.
https://pointclouds.org/documentation/classpcl_1_1tracking_1_1_k_l_d_adaptive_particle_filter_tracker.html