Point Cloud Library (PCL)
1.14.1-dev
|
ParticleFilterTracker tracks the PointCloud which is given by setReferenceCloud within the measured PointCloud using particle filter method. More...
#include <pcl/tracking/particle_filter.h>
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 . 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< 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_ {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... | |
ParticleFilterTracker tracks the PointCloud which is given by setReferenceCloud within the measured PointCloud using particle filter method.
Definition at line 19 of file particle_filter.h.
using pcl::tracking::ParticleFilterTracker< PointInT, StateT >::BaseClass = Tracker<PointInT, StateT> |
Definition at line 33 of file particle_filter.h.
using pcl::tracking::ParticleFilterTracker< PointInT, StateT >::CloudCoherence = PointCloudCoherence<PointInT> |
Definition at line 47 of file particle_filter.h.
using pcl::tracking::ParticleFilterTracker< PointInT, StateT >::CloudCoherenceConstPtr = typename CloudCoherence::ConstPtr |
Definition at line 49 of file particle_filter.h.
using pcl::tracking::ParticleFilterTracker< PointInT, StateT >::CloudCoherencePtr = typename CloudCoherence::Ptr |
Definition at line 48 of file particle_filter.h.
using pcl::tracking::ParticleFilterTracker< PointInT, StateT >::Coherence = PointCoherence<PointInT> |
Definition at line 43 of file particle_filter.h.
using pcl::tracking::ParticleFilterTracker< PointInT, StateT >::CoherenceConstPtr = typename Coherence::ConstPtr |
Definition at line 45 of file particle_filter.h.
using pcl::tracking::ParticleFilterTracker< PointInT, StateT >::CoherencePtr = typename Coherence::Ptr |
Definition at line 44 of file particle_filter.h.
using pcl::tracking::ParticleFilterTracker< PointInT, StateT >::ConstPtr = shared_ptr<const ParticleFilterTracker<PointInT, StateT> > |
Definition at line 31 of file particle_filter.h.
using pcl::tracking::ParticleFilterTracker< PointInT, StateT >::PointCloudIn = typename Tracker<PointInT, StateT>::PointCloudIn |
Definition at line 35 of file particle_filter.h.
using pcl::tracking::ParticleFilterTracker< PointInT, StateT >::PointCloudInConstPtr = typename PointCloudIn::ConstPtr |
Definition at line 37 of file particle_filter.h.
using pcl::tracking::ParticleFilterTracker< PointInT, StateT >::PointCloudInPtr = typename PointCloudIn::Ptr |
Definition at line 36 of file particle_filter.h.
using pcl::tracking::ParticleFilterTracker< PointInT, StateT >::PointCloudState = typename Tracker<PointInT, StateT>::PointCloudState |
Definition at line 39 of file particle_filter.h.
using pcl::tracking::ParticleFilterTracker< PointInT, StateT >::PointCloudStateConstPtr = typename PointCloudState::ConstPtr |
Definition at line 41 of file particle_filter.h.
using pcl::tracking::ParticleFilterTracker< PointInT, StateT >::PointCloudStatePtr = typename PointCloudState::Ptr |
Definition at line 40 of file particle_filter.h.
using pcl::tracking::ParticleFilterTracker< PointInT, StateT >::Ptr = shared_ptr<ParticleFilterTracker<PointInT, StateT> > |
Definition at line 30 of file particle_filter.h.
|
inline |
Empty constructor.
Definition at line 52 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::pass_x_, pcl::tracking::ParticleFilterTracker< PointInT, StateT >::pass_y_, pcl::tracking::ParticleFilterTracker< PointInT, StateT >::pass_z_, pcl::PassThrough< PointT >::setFilterFieldName(), pcl::FilterIndices< PointT >::setKeepOrganized(), and pcl::tracking::Tracker< PointInT, StateT >::tracker_name_.
|
protected |
Compute the parameters for the bounding box of hypothesis pointclouds.
[out] | x_min | the minimum value of x axis. |
[out] | x_max | the maximum value of x axis. |
[out] | y_min | the minimum value of y axis. |
[out] | y_max | the maximum value of y axis. |
[out] | z_min | the minimum value of z axis. |
[out] | z_max | the maximum value of z axis. |
Definition at line 187 of file particle_filter.hpp.
References pcl::getMinMax3D().
|
overrideprotectedvirtual |
Track the pointcloud using particle filter method.
Implements pcl::tracking::Tracker< PointInT, StateT >.
Definition at line 379 of file particle_filter.hpp.
|
protected |
Compute a reference pointcloud transformed to the pose that hypothesis represents.
[in] | hypothesis | a particle which represents a hypothesis. |
[in] | indices | the indices which should be taken into account. |
[out] | cloud | the resultant point cloud model dataset which is transformed to hypothesis. |
Definition at line 275 of file particle_filter.hpp.
|
protected |
Compute a reference pointcloud transformed to the pose that hypothesis represents and calculate indices taking occlusion into account.
[in] | hypothesis | a particle which represents a hypothesis. |
[in] | indices | the indices which should be taken into account. |
[out] | cloud | the resultant point cloud model dataset which is transformed to hypothesis. |
Definition at line 298 of file particle_filter.hpp.
References pcl::getAngle3D().
|
protected |
Compute a reference pointcloud transformed to the pose that hypothesis represents and calculate indices without taking occlusion into account.
[in] | hypothesis | a particle which represents a hypothesis. |
[out] | cloud | the resultant point cloud model dataset which is transformed to hypothesis. |
Definition at line 286 of file particle_filter.hpp.
|
protected |
Crop the pointcloud by the bounding box calculated from hypothesis and the reference pointcloud.
[in] | cloud | a pointer to pointcloud to be cropped. |
[out] | output | a pointer to be assigned the cropped pointcloud. |
Definition at line 162 of file particle_filter.hpp.
|
protected |
Generate the tables for walker's alias method.
Definition at line 58 of file particle_filter.hpp.
|
inline |
Get the value of alpha.
Definition at line 262 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::alpha_.
|
inline |
Get the PointCloudCoherence to compute likelihood.
Definition at line 123 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::coherence_.
|
inline |
Get the adjustment ratio.
Definition at line 375 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::fit_ratio_.
|
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_.
|
inline |
Get the number of iteration.
Definition at line 75 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::iteration_num_.
|
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_.
|
inline |
Get the motion ratio.
Definition at line 317 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::motion_ratio_.
|
inline |
Get the number of the particles.
Definition at line 91 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::particle_num_.
|
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_.
|
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_.
|
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_.
|
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_.
|
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_.
|
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_.
|
inline |
Get the value of use_normal_.
Definition at line 285 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::use_normal_.
|
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.
|
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.
|
inline |
Normalize the weight of a particle using .
[in] | w | the weight to be normalized |
[in] | w_min | the minimum weight of the particles |
[in] | w_max | the maximum weight of the particles |
Definition at line 246 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::alpha_.
|
protectedvirtual |
Normalize the weights of all the particels.
Definition at line 117 of file particle_filter.hpp.
|
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.
|
protected |
Resampling the particle in deterministic way.
|
protected |
Resampling the particle with replacement.
Definition at line 328 of file particle_filter.hpp.
|
inlinevirtual |
Reset the particles to restart tracking.
Definition at line 382 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::particles_.
|
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}, }
a | an alias table, which generated by genAliasTable. |
q | a table of weight, which generated by genAliasTable. |
Definition at line 42 of file particle_filter.hpp.
|
inline |
Set the value of alpha.
[in] | alpha | the value of alpha |
Definition at line 255 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::alpha_.
|
inline |
Set the PointCloudCoherence as likelihood.
[in] | coherence | a pointer to PointCloudCoherence. |
Definition at line 116 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::coherence_.
|
inline |
Set the covariance of the initial noise.
It will be used when initializing the particles.
[in] | initial_noise_covariance | the 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_.
|
inline |
Set the mean of the initial noise.
It will be used when initializing the particles.
[in] | initial_noise_mean | the mean values of initial noise. |
Definition at line 154 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::initial_noise_mean_.
|
inline |
Set the number of interval frames to run change detection.
[in] | change_detector_interval | the number of interval frames. |
Definition at line 326 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::change_detector_interval_.
|
inline |
Set the number of iteration.
[in] | iteration_num | the number of iteration. |
Definition at line 68 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::iteration_num_.
|
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.
[in] | min_indices | the minimum number of indices. |
Definition at line 185 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::min_indices_.
|
inline |
Set the minimum amount of points required within leaf node to become serialized in change detection.
[in] | change_detector_filter | the 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_.
|
inline |
Set the motion ratio.
[in] | motion_ratio | the ratio of hypothesis to use motion model. |
Definition at line 310 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::motion_ratio_.
|
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.
[in] | occlusion_angle_thr | threshold of angle to be considered occlusion. |
Definition at line 174 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::occlusion_angle_thr_.
|
inline |
Set the number of the particles.
[in] | particle_num | the number of the particles. |
Definition at line 84 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::particle_num_.
|
inline |
Set a pointer to a reference dataset to be tracked.
[in] | ref | a pointer to a PointCloud message |
Definition at line 100 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::ref_.
|
inline |
Set the threshold to re-initialize the particles.
[in] | resample_likelihood_thr | threshold to re-initialize. |
Definition at line 163 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::resample_likelihood_thr_.
|
inline |
Set the resolution of change detection.
[in] | resolution | resolution of change detection octree |
Definition at line 353 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::change_detector_resolution_.
|
inline |
Set the covariance of step noise.
[in] | step_noise_covariance | the 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_.
|
inline |
Set the transformation from the world coordinates to the frame of the particles.
[in] | trans | Affine 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_.
|
inline |
Set the value of use_change_detector_.
[in] | use_change_detector | the value of use_change_detector_. |
Definition at line 294 of file particle_filter.h.
References pcl::tracking::ParticleFilterTracker< PointInT, StateT >::use_change_detector_.
|
inline |
Set the value of use_normal_.
[in] | use_normal | the 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_.
|
protected |
Run change detection and return true if there is a change.
[in] | input | a pointer to the input pointcloud. |
Definition at line 218 of file particle_filter.hpp.
|
inline |
Convert a state to affine transformation from the world coordinates frame.
[in] | particle | an instance of StateT. |
Definition at line 225 of file particle_filter.h.
|
protectedvirtual |
Calculate the weighted mean of the particles and set it as the result.
Definition at line 366 of file particle_filter.hpp.
|
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.
|
protected |
The weight to be used in normalization of the weights of the particles.
Definition at line 579 of file particle_filter.h.
Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getAlpha(), pcl::tracking::ParticleFilterTracker< PointInT, StateT >::normalizeParticleWeight(), and pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setAlpha().
|
protected |
A counter to skip change detection.
Definition at line 618 of file particle_filter.h.
|
protected |
Change detector used as a trigger to track.
Definition at line 611 of file particle_filter.h.
|
protected |
Minimum points in a leaf when calling change detector.
defaults to 10.
Definition at line 622 of file particle_filter.h.
Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getMinPointsOfChangeDetection(), and pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setMinPointsOfChangeDetection().
|
protected |
The number of interval frame to run change detection.
defaults to 10.
Definition at line 626 of file particle_filter.h.
Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getIntervalOfChangeDetection(), and pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setIntervalOfChangeDetection().
|
protected |
Resolution of change detector.
defaults to 0.01.
Definition at line 629 of file particle_filter.h.
Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getResolutionOfChangeDetection(), and pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setResolutionOfChangeDetection().
|
protected |
A flag to be true when change of pointclouds is detected.
Definition at line 615 of file particle_filter.h.
|
protected |
A pointer to PointCloudCoherence.
Definition at line 556 of file particle_filter.h.
Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getCloudCoherence(), and pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setCloudCoherence().
|
protected |
Adjustment of the particle filter.
Definition at line 547 of file particle_filter.h.
Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getFitRatio().
|
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().
|
protected |
The mean values of initial noise.
Definition at line 569 of file particle_filter.h.
Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setInitialNoiseMean().
|
protected |
The number of iteration of particlefilter.
Definition at line 538 of file particle_filter.h.
Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getIterationNum(), and pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setIterationNum().
|
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().
|
protected |
Difference between the result in t and t-1.
Definition at line 592 of file particle_filter.h.
|
protected |
Ratio of hypothesis to use motion model.
Definition at line 595 of file particle_filter.h.
Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getMotionRatio(), and pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setMotionRatio().
|
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().
|
protected |
The number of the particles.
Definition at line 541 of file particle_filter.h.
Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getParticleNum(), and pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setParticleNum().
|
protected |
A pointer to the particles
Definition at line 553 of file particle_filter.h.
Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getParticles(), and pcl::tracking::ParticleFilterTracker< PointInT, StateT >::resetTracking().
|
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().
|
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().
|
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().
|
protected |
A pointer to reference point cloud.
Definition at line 550 of file particle_filter.h.
Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getReferenceCloud(), and pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setReferenceCloud().
|
protected |
The result of tracking.
Definition at line 582 of file particle_filter.h.
Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getResult().
|
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().
|
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().
|
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().
|
protected |
A list of the pointers to pointclouds.
Definition at line 608 of file particle_filter.h.
|
protected |
The flag which will be true if using change detection.
Definition at line 632 of file particle_filter.h.
Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getUseChangeDetector(), and pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setUseChangeDetector().
|
protected |
A flag to use normal or not.
defaults to false.
Definition at line 589 of file particle_filter.h.
Referenced by pcl::tracking::ParticleFilterTracker< PointInT, StateT >::getUseNormal(), and pcl::tracking::ParticleFilterTracker< PointInT, StateT >::setUseNormal().