Point Cloud Library (PCL)  1.14.0-dev
List of all members | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
pcl::tracking::ParticleFilterTracker< PointInT, StateT > Class Template Reference

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

#include <pcl/tracking/particle_filter.h>

+ Inheritance diagram for pcl::tracking::ParticleFilterTracker< PointInT, StateT >:
+ Collaboration diagram for pcl::tracking::ParticleFilterTracker< PointInT, StateT >:

Public Types

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

 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...
 
PointCloudInConstPtr const 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...
 
PointCloudConstPtr const 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...
 
IndicesConstPtr const 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

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 actual computation. More...
 
virtual void weight ()
 Weighting phase of particle filter method. More...
 
virtual void resample ()
 Resampling 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

int iteration_num_ {1}
 The number of iteration of particlefilter. More...
 
int particle_num_ {0}
 The number of the particles. More...
 
int min_indices_ {1}
 The minimum number of points which the hypothesis should have. More...
 
double fit_ratio_ {0.0}
 Adjustment of the particle filter. More...
 
PointCloudInConstPtr ref_ {nullptr}
 A pointer to reference point cloud. More...
 
PointCloudStatePtr particles_ {nullptr}
 A pointer to the particles
More...
 
CloudCoherencePtr coherence_ {nullptr}
 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_ {0.0}
 The threshold for the particles to be re-initialized. More...
 
double occlusion_angle_thr_ {M_PI / 2.0}
 The threshold for the points to be considered as occluded. More...
 
double alpha_ {15.0}
 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_ {false}
 A flag to use normal or not. More...
 
StateT motion_
 Difference between the result in t and t-1. More...
 
double motion_ratio_ {0.25}
 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< PointCloudInPtrtransed_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_ {false}
 A flag to be true when change of pointclouds is detected. More...
 
unsigned int change_counter_ {0}
 A counter to skip change detection. More...
 
unsigned int change_detector_filter_ {10}
 Minimum points in a leaf when calling change detector. More...
 
unsigned int change_detector_interval_ {10}
 The number of interval frame to run change detection. More...
 
double change_detector_resolution_ {0.01}
 Resolution of change detector. More...
 
bool use_change_detector_ {false}
 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::ParticleFilterTracker< PointInT, StateT >

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

Author
Ryohei Ueda

Definition at line 19 of file particle_filter.h.

Member Typedef Documentation

◆ BaseClass

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

Definition at line 33 of file particle_filter.h.

◆ CloudCoherence

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

Definition at line 47 of file particle_filter.h.

◆ CloudCoherenceConstPtr

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

Definition at line 49 of file particle_filter.h.

◆ CloudCoherencePtr

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

Definition at line 48 of file particle_filter.h.

◆ Coherence

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

Definition at line 43 of file particle_filter.h.

◆ CoherenceConstPtr

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

Definition at line 45 of file particle_filter.h.

◆ CoherencePtr

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

Definition at line 44 of file particle_filter.h.

◆ ConstPtr

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

Definition at line 31 of file particle_filter.h.

◆ PointCloudIn

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

Definition at line 35 of file particle_filter.h.

◆ PointCloudInConstPtr

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

Definition at line 37 of file particle_filter.h.

◆ PointCloudInPtr

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

Definition at line 36 of file particle_filter.h.

◆ PointCloudState

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

Definition at line 39 of file particle_filter.h.

◆ PointCloudStateConstPtr

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

Definition at line 41 of file particle_filter.h.

◆ PointCloudStatePtr

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

Definition at line 40 of file particle_filter.h.

◆ Ptr

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

Definition at line 30 of file particle_filter.h.

Constructor & Destructor Documentation

◆ ParticleFilterTracker()

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

Member Function Documentation

◆ calcBoundingBox()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::calcBoundingBox ( double &  x_min,
double &  x_max,
double &  y_min,
double &  y_max,
double &  z_min,
double &  z_max 
)
protected

Compute the parameters for the bounding box of hypothesis pointclouds.

Parameters
[out]x_minthe minimum value of x axis.
[out]x_maxthe maximum value of x axis.
[out]y_minthe minimum value of y axis.
[out]y_maxthe maximum value of y axis.
[out]z_minthe minimum value of z axis.
[out]z_maxthe maximum value of z axis.

Definition at line 187 of file particle_filter.hpp.

References pcl::getMinMax3D().

◆ computeTracking()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::computeTracking
overrideprotectedvirtual

Track the pointcloud using particle filter method.

Implements pcl::tracking::Tracker< PointInT, StateT >.

Definition at line 379 of file particle_filter.hpp.

◆ computeTransformedPointCloud()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::computeTransformedPointCloud ( const StateT &  hypothesis,
pcl::Indices indices,
PointCloudIn cloud 
)
protected

Compute a reference pointcloud transformed to the pose that hypothesis represents.

Parameters
[in]hypothesisa particle which represents a hypothesis.
[in]indicesthe indices which should be taken into account.
[out]cloudthe resultant point cloud model dataset which is transformed to hypothesis.

Definition at line 275 of file particle_filter.hpp.

◆ computeTransformedPointCloudWithNormal()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::computeTransformedPointCloudWithNormal ( const StateT &  hypothesis,
pcl::Indices indices,
PointCloudIn cloud 
)
protected

Compute a reference pointcloud transformed to the pose that hypothesis represents and calculate indices taking occlusion into account.

Parameters
[in]hypothesisa particle which represents a hypothesis.
[in]indicesthe indices which should be taken into account.
[out]cloudthe resultant point cloud model dataset which is transformed to hypothesis.

Definition at line 298 of file particle_filter.hpp.

References pcl::getAngle3D().

◆ computeTransformedPointCloudWithoutNormal()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::computeTransformedPointCloudWithoutNormal ( const StateT &  hypothesis,
PointCloudIn cloud 
)
protected

Compute a reference pointcloud transformed to the pose that hypothesis represents and calculate indices without taking occlusion into account.

Parameters
[in]hypothesisa particle which represents a hypothesis.
[out]cloudthe resultant point cloud model dataset which is transformed to hypothesis.

Definition at line 286 of file particle_filter.hpp.

◆ cropInputPointCloud()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::cropInputPointCloud ( const PointCloudInConstPtr cloud,
PointCloudIn output 
)
protected

Crop the pointcloud by the bounding box calculated from hypothesis and the reference pointcloud.

Parameters
[in]clouda pointer to pointcloud to be cropped.
[out]outputa pointer to be assigned the cropped pointcloud.

Definition at line 162 of file particle_filter.hpp.

◆ genAliasTable()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::genAliasTable ( std::vector< int > &  a,
std::vector< double > &  q,
const PointCloudStateConstPtr particles 
)
protected

Generate the tables for walker's alias method.

Definition at line 58 of file particle_filter.hpp.

◆ getAlpha()

template<typename PointInT , typename StateT >
double pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getAlpha ( )
inline

Get the value of alpha.

Definition at line 262 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::alpha_.

◆ getCloudCoherence()

template<typename PointInT , typename StateT >
CloudCoherencePtr pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getCloudCoherence ( ) const
inline

Get the PointCloudCoherence to compute likelihood.

Definition at line 123 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::coherence_.

◆ getFitRatio()

template<typename PointInT , typename StateT >
double pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getFitRatio ( ) const
inline

Get the adjustment ratio.

Definition at line 375 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::fit_ratio_.

◆ getIntervalOfChangeDetection()

template<typename PointInT , typename StateT >
unsigned int pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getIntervalOfChangeDetection ( )
inline

Get the number of interval frames to run change detection.

Definition at line 333 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::change_detector_interval_.

◆ getIterationNum()

template<typename PointInT , typename StateT >
int pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getIterationNum ( ) const
inline

Get the number of iteration.

Definition at line 75 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::iteration_num_.

◆ getMinPointsOfChangeDetection()

template<typename PointInT , typename StateT >
unsigned int pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getMinPointsOfChangeDetection ( )
inline

Get the minimum amount of points required within leaf node to become serialized in change detection.

Definition at line 368 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::change_detector_filter_.

◆ getMotionRatio()

template<typename PointInT , typename StateT >
double pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getMotionRatio ( )
inline

Get the motion ratio.

Definition at line 317 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::motion_ratio_.

◆ getParticleNum()

template<typename PointInT , typename StateT >
int pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getParticleNum ( ) const
inline

Get the number of the particles.

Definition at line 91 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::particle_num_.

◆ getParticles()

template<typename PointInT , typename StateT >
PointCloudStatePtr pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getParticles ( ) const
inline

Get a pointer to a pointcloud of the particles.

Definition at line 232 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::particles_.

◆ getReferenceCloud()

template<typename PointInT , typename StateT >
PointCloudInConstPtr const pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getReferenceCloud ( )
inline

Get a pointer to a reference dataset to be tracked.

Definition at line 107 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::ref_.

◆ getResolutionOfChangeDetection()

template<typename PointInT , typename StateT >
double pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getResolutionOfChangeDetection ( )
inline

Get the resolution of change detection.

Definition at line 360 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::change_detector_resolution_.

◆ getResult()

template<typename PointInT , typename StateT >
StateT pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getResult ( ) const
inlineoverridevirtual

Get an instance of the result of tracking.

This function returns the particle that represents the transform between the reference point cloud at the beginning and the best guess about its location in the most recent frame.

Implements pcl::tracking::Tracker< PointInT, StateT >.

Definition at line 215 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::representative_state_.

◆ getTrans()

template<typename PointInT , typename StateT >
Eigen::Affine3f pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getTrans ( ) const
inline

Get the transformation from the world coordinates to the frame of the particles.

Definition at line 204 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::trans_.

◆ getUseChangeDetector()

template<typename PointInT , typename StateT >
bool pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getUseChangeDetector ( )
inline

Get the value of use_change_detector_.

Definition at line 301 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::use_change_detector_.

◆ getUseNormal()

template<typename PointInT , typename StateT >
bool pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getUseNormal ( )
inline

Get the value of use_normal_.

Definition at line 285 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::use_normal_.

◆ initCompute()

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

This method should get called before starting the actual computation.

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

Definition at line 14 of file particle_filter.hpp.

◆ initParticles()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::initParticles ( bool  reset)
protected

Initialize the particles.

initial_noise_covariance_ and initial_noise_mean_ are used for Gaussian sampling.

Definition at line 94 of file particle_filter.hpp.

◆ normalizeParticleWeight()

template<typename PointInT , typename StateT >
double pcl::tracking::ParticleFilterTracker< PointInT, StateT >::normalizeParticleWeight ( double  w,
double  w_min,
double  w_max 
)
inline

Normalize the weight of a particle using $ std::exp(1- alpha ( w - w_{min}) / (w_max - w_min)) $.

Note
This method is described in [P.Azad et. al, ICRA11].
Parameters
[in]wthe weight to be normalized
[in]w_minthe minimum weight of the particles
[in]w_maxthe maximum weight of the particles

Definition at line 246 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::alpha_.

◆ normalizeWeight()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::normalizeWeight
protectedvirtual

Normalize the weights of all the particels.

Definition at line 117 of file particle_filter.hpp.

◆ resample()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::resample
protectedvirtual

Resampling phase of particle filter method.

Sampling the particles according to the weights calculated in weight method. In particular, "sample with replacement" is achieved by walker's alias method.

Reimplemented in pcl::tracking::KLDAdaptiveParticleFilterTracker< PointInT, StateT >.

Definition at line 321 of file particle_filter.hpp.

◆ resampleDeterministic()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::resampleDeterministic ( )
protected

Resampling the particle in deterministic way.

◆ resampleWithReplacement()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::resampleWithReplacement
protected

Resampling the particle with replacement.

Definition at line 328 of file particle_filter.hpp.

◆ resetTracking()

template<typename PointInT , typename StateT >
virtual void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::resetTracking ( )
inlinevirtual

Reset the particles to restart tracking.

Definition at line 382 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::particles_.

◆ sampleWithReplacement()

template<typename PointInT , typename StateT >
int pcl::tracking::ParticleFilterTracker< PointInT, StateT >::sampleWithReplacement ( const std::vector< int > &  a,
const std::vector< double > &  q 
)
protected

Implementation of "sample with replacement" using Walker's alias method.

about Walker's alias method, you can check the paper below: article{355749}, author = {Walker, Alastair J.}, title = {An Efficient Method for Generating Discrete Random Variables with General Distributions}, journal = {ACM Trans. Math. Softw.}, volume = {3}, number = {3}, year = {1977}, issn = {0098-3500}, pages = {253–256}, doi = {http://doi.acm.org/10.1145/355744.355749}, publisher = {ACM}, address = {New York, NY, USA}, }

Parameters
aan alias table, which generated by genAliasTable.
qa table of weight, which generated by genAliasTable.

Definition at line 42 of file particle_filter.hpp.

◆ setAlpha()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setAlpha ( double  alpha)
inline

Set the value of alpha.

Parameters
[in]alphathe value of alpha

Definition at line 255 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::alpha_.

◆ setCloudCoherence()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setCloudCoherence ( const CloudCoherencePtr coherence)
inline

Set the PointCloudCoherence as likelihood.

Parameters
[in]coherencea pointer to PointCloudCoherence.

Definition at line 116 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::coherence_.

◆ setInitialNoiseCovariance()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setInitialNoiseCovariance ( const std::vector< double > &  initial_noise_covariance)
inline

Set the covariance of the initial noise.

It will be used when initializing the particles.

Parameters
[in]initial_noise_covariancethe diagonal elements of covariance matrix of initial noise.

Definition at line 144 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::initial_noise_covariance_.

◆ setInitialNoiseMean()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setInitialNoiseMean ( const std::vector< double > &  initial_noise_mean)
inline

Set the mean of the initial noise.

It will be used when initializing the particles.

Parameters
[in]initial_noise_meanthe mean values of initial noise.

Definition at line 154 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::initial_noise_mean_.

◆ setIntervalOfChangeDetection()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setIntervalOfChangeDetection ( unsigned int  change_detector_interval)
inline

Set the number of interval frames to run change detection.

Parameters
[in]change_detector_intervalthe number of interval frames.

Definition at line 326 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::change_detector_interval_.

◆ setIterationNum()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setIterationNum ( const int  iteration_num)
inline

Set the number of iteration.

Parameters
[in]iteration_numthe number of iteration.

Definition at line 68 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::iteration_num_.

◆ setMinIndices()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setMinIndices ( const int  min_indices)
inline

Set the minimum number of indices (default: 1).

ParticleFilterTracker does not take into account the hypothesis whose the number of points is smaller than the minimum indices.

Parameters
[in]min_indicesthe minimum number of indices.

Definition at line 185 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::min_indices_.

◆ setMinPointsOfChangeDetection()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setMinPointsOfChangeDetection ( unsigned int  change_detector_filter)
inline

Set the minimum amount of points required within leaf node to become serialized in change detection.

Parameters
[in]change_detector_filterthe minimum amount of points required within leaf node

Definition at line 344 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::change_detector_filter_.

◆ setMotionRatio()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setMotionRatio ( double  motion_ratio)
inline

Set the motion ratio.

Parameters
[in]motion_ratiothe ratio of hypothesis to use motion model.

Definition at line 310 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::motion_ratio_.

◆ setOcclusionAngleThe()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setOcclusionAngleThe ( const double  occlusion_angle_thr)
inline

Set the threshold of angle to be considered occlusion (default: pi/2).

ParticleFilterTracker does not take the occluded points into account according to the angle between the normal and the position.

Parameters
[in]occlusion_angle_thrthreshold of angle to be considered occlusion.

Definition at line 174 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::occlusion_angle_thr_.

◆ setParticleNum()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setParticleNum ( const int  particle_num)
inline

Set the number of the particles.

Parameters
[in]particle_numthe number of the particles.

Definition at line 84 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::particle_num_.

◆ setReferenceCloud()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setReferenceCloud ( const PointCloudInConstPtr ref)
inline

Set a pointer to a reference dataset to be tracked.

Parameters
[in]refa pointer to a PointCloud message

Definition at line 100 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::ref_.

◆ setResampleLikelihoodThr()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setResampleLikelihoodThr ( const double  resample_likelihood_thr)
inline

Set the threshold to re-initialize the particles.

Parameters
[in]resample_likelihood_thrthreshold to re-initialize.

Definition at line 163 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::resample_likelihood_thr_.

◆ setResolutionOfChangeDetection()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setResolutionOfChangeDetection ( double  resolution)
inline

Set the resolution of change detection.

Parameters
[in]resolutionresolution of change detection octree

Definition at line 353 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::change_detector_resolution_.

◆ setStepNoiseCovariance()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setStepNoiseCovariance ( const std::vector< double > &  step_noise_covariance)
inline

Set the covariance of step noise.

Parameters
[in]step_noise_covariancethe diagonal elements of covariance matrix of step noise.

Definition at line 133 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::step_noise_covariance_.

◆ setTrans()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setTrans ( const Eigen::Affine3f &  trans)
inline

Set the transformation from the world coordinates to the frame of the particles.

Parameters
[in]transAffine transformation from the worldcoordinates to the frame of the particles.

Definition at line 196 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::trans_.

◆ setUseChangeDetector()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setUseChangeDetector ( bool  use_change_detector)
inline

Set the value of use_change_detector_.

Parameters
[in]use_change_detectorthe value of use_change_detector_.

Definition at line 294 of file particle_filter.h.

References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::use_change_detector_.

◆ setUseNormal()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setUseNormal ( bool  use_normal)
inline

Set the value of use_normal_.

Parameters
[in]use_normalthe value of use_normal_.

Definition at line 271 of file particle_filter.h.

References pcl::tracking::Tracker< PointInT, StateT >::getClassName(), and pcl::tracking::ParticleFilterTracker< PointInT, StateT >::use_normal_.

◆ testChangeDetection()

template<typename PointInT , typename StateT >
bool pcl::tracking::ParticleFilterTracker< PointInT, StateT >::testChangeDetection ( const PointCloudInConstPtr input)
protected

Run change detection and return true if there is a change.

Parameters
[in]inputa pointer to the input pointcloud.

Definition at line 218 of file particle_filter.hpp.

◆ toEigenMatrix()

template<typename PointInT , typename StateT >
Eigen::Affine3f pcl::tracking::ParticleFilterTracker< PointInT, StateT >::toEigenMatrix ( const StateT &  particle)
inline

Convert a state to affine transformation from the world coordinates frame.

Parameters
[in]particlean instance of StateT.

Definition at line 225 of file particle_filter.h.

◆ update()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::update
protectedvirtual

Calculate the weighted mean of the particles and set it as the result.

Definition at line 366 of file particle_filter.hpp.

◆ weight()

template<typename PointInT , typename StateT >
void pcl::tracking::ParticleFilterTracker< PointInT, StateT >::weight
protectedvirtual

Weighting phase of particle filter method.

Calculate the likelihood of all of the particles and set the weights.

Reimplemented in pcl::tracking::ParticleFilterOMPTracker< PointInT, StateT >, and pcl::tracking::KLDAdaptiveParticleFilterOMPTracker< PointInT, StateT >.

Definition at line 232 of file particle_filter.hpp.

Member Data Documentation

◆ alpha_

template<typename PointInT , typename StateT >
double pcl::tracking::ParticleFilterTracker< PointInT, StateT >::alpha_ {15.0}
protected

◆ change_counter_

template<typename PointInT , typename StateT >
unsigned int pcl::tracking::ParticleFilterTracker< PointInT, StateT >::change_counter_ {0}
protected

A counter to skip change detection.

Definition at line 618 of file particle_filter.h.

◆ change_detector_

template<typename PointInT , typename StateT >
pcl::octree::OctreePointCloudChangeDetector<PointInT>::Ptr pcl::tracking::ParticleFilterTracker< PointInT, StateT >::change_detector_
protected
Initial value:
{
nullptr}

Change detector used as a trigger to track.

Definition at line 611 of file particle_filter.h.

◆ change_detector_filter_

template<typename PointInT , typename StateT >
unsigned int pcl::tracking::ParticleFilterTracker< PointInT, StateT >::change_detector_filter_ {10}
protected

◆ change_detector_interval_

template<typename PointInT , typename StateT >
unsigned int pcl::tracking::ParticleFilterTracker< PointInT, StateT >::change_detector_interval_ {10}
protected

◆ change_detector_resolution_

template<typename PointInT , typename StateT >
double pcl::tracking::ParticleFilterTracker< PointInT, StateT >::change_detector_resolution_ {0.01}
protected

◆ changed_

template<typename PointInT , typename StateT >
bool pcl::tracking::ParticleFilterTracker< PointInT, StateT >::changed_ {false}
protected

A flag to be true when change of pointclouds is detected.

Definition at line 615 of file particle_filter.h.

◆ coherence_

template<typename PointInT , typename StateT >
CloudCoherencePtr pcl::tracking::ParticleFilterTracker< PointInT, StateT >::coherence_ {nullptr}
protected

◆ fit_ratio_

template<typename PointInT , typename StateT >
double pcl::tracking::ParticleFilterTracker< PointInT, StateT >::fit_ratio_ {0.0}
protected

Adjustment of the particle filter.

Definition at line 547 of file particle_filter.h.

Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getFitRatio().

◆ initial_noise_covariance_

template<typename PointInT , typename StateT >
std::vector<double> pcl::tracking::ParticleFilterTracker< PointInT, StateT >::initial_noise_covariance_ {}
protected

The diagonal elements of covariance matrix of the initial noise.

the covariance matrix is used when initialize the particles.

Definition at line 566 of file particle_filter.h.

Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setInitialNoiseCovariance().

◆ initial_noise_mean_

template<typename PointInT , typename StateT >
std::vector<double> pcl::tracking::ParticleFilterTracker< PointInT, StateT >::initial_noise_mean_ {}
protected

The mean values of initial noise.

Definition at line 569 of file particle_filter.h.

Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setInitialNoiseMean().

◆ iteration_num_

template<typename PointInT , typename StateT >
int pcl::tracking::ParticleFilterTracker< PointInT, StateT >::iteration_num_ {1}
protected

◆ min_indices_

template<typename PointInT , typename StateT >
int pcl::tracking::ParticleFilterTracker< PointInT, StateT >::min_indices_ {1}
protected

The minimum number of points which the hypothesis should have.

Definition at line 544 of file particle_filter.h.

Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setMinIndices().

◆ motion_

template<typename PointInT , typename StateT >
StateT pcl::tracking::ParticleFilterTracker< PointInT, StateT >::motion_
protected

Difference between the result in t and t-1.

Definition at line 592 of file particle_filter.h.

◆ motion_ratio_

template<typename PointInT , typename StateT >
double pcl::tracking::ParticleFilterTracker< PointInT, StateT >::motion_ratio_ {0.25}
protected

◆ occlusion_angle_thr_

template<typename PointInT , typename StateT >
double pcl::tracking::ParticleFilterTracker< PointInT, StateT >::occlusion_angle_thr_ {M_PI / 2.0}
protected

The threshold for the points to be considered as occluded.

Definition at line 575 of file particle_filter.h.

Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setOcclusionAngleThe().

◆ particle_num_

template<typename PointInT , typename StateT >
int pcl::tracking::ParticleFilterTracker< PointInT, StateT >::particle_num_ {0}
protected

◆ particles_

template<typename PointInT , typename StateT >
PointCloudStatePtr pcl::tracking::ParticleFilterTracker< PointInT, StateT >::particles_ {nullptr}
protected

◆ pass_x_

template<typename PointInT , typename StateT >
pcl::PassThrough<PointInT> pcl::tracking::ParticleFilterTracker< PointInT, StateT >::pass_x_
protected

Pass through filter to crop the pointclouds within the hypothesis bounding box.

Definition at line 599 of file particle_filter.h.

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

◆ pass_y_

template<typename PointInT , typename StateT >
pcl::PassThrough<PointInT> pcl::tracking::ParticleFilterTracker< PointInT, StateT >::pass_y_
protected

Pass through filter to crop the pointclouds within the hypothesis bounding box.

Definition at line 602 of file particle_filter.h.

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

◆ pass_z_

template<typename PointInT , typename StateT >
pcl::PassThrough<PointInT> pcl::tracking::ParticleFilterTracker< PointInT, StateT >::pass_z_
protected

Pass through filter to crop the pointclouds within the hypothesis bounding box.

Definition at line 605 of file particle_filter.h.

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

◆ ref_

template<typename PointInT , typename StateT >
PointCloudInConstPtr pcl::tracking::ParticleFilterTracker< PointInT, StateT >::ref_ {nullptr}
protected

◆ representative_state_

template<typename PointInT , typename StateT >
StateT pcl::tracking::ParticleFilterTracker< PointInT, StateT >::representative_state_
protected

The result of tracking.

Definition at line 582 of file particle_filter.h.

Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getResult().

◆ resample_likelihood_thr_

template<typename PointInT , typename StateT >
double pcl::tracking::ParticleFilterTracker< PointInT, StateT >::resample_likelihood_thr_ {0.0}
protected

The threshold for the particles to be re-initialized.

Definition at line 572 of file particle_filter.h.

Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setResampleLikelihoodThr().

◆ step_noise_covariance_

template<typename PointInT , typename StateT >
std::vector<double> pcl::tracking::ParticleFilterTracker< PointInT, StateT >::step_noise_covariance_ {}
protected

The diagonal elements of covariance matrix of the step noise.

the covariance matrix is used at every resample method.

Definition at line 561 of file particle_filter.h.

Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setStepNoiseCovariance().

◆ trans_

template<typename PointInT , typename StateT >
Eigen::Affine3f pcl::tracking::ParticleFilterTracker< PointInT, StateT >::trans_
protected

An affine transformation from the world coordinates frame to the origin of the particles.

Definition at line 586 of file particle_filter.h.

Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getTrans(), and pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setTrans().

◆ transed_reference_vector_

template<typename PointInT , typename StateT >
std::vector<PointCloudInPtr> pcl::tracking::ParticleFilterTracker< PointInT, StateT >::transed_reference_vector_ {}
protected

A list of the pointers to pointclouds.

Definition at line 608 of file particle_filter.h.

◆ use_change_detector_

template<typename PointInT , typename StateT >
bool pcl::tracking::ParticleFilterTracker< PointInT, StateT >::use_change_detector_ {false}
protected

◆ use_normal_

template<typename PointInT , typename StateT >
bool pcl::tracking::ParticleFilterTracker< PointInT, StateT >::use_normal_ {false}
protected

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