Point Cloud Library (PCL)
1.14.1-dev
|
ParticleFilterOMPTracker tracks the PointCloud which is given by setReferenceCloud within the measured PointCloud using particle filter method in parallel, using the OpenMP standard. More...
#include <pcl/tracking/particle_filter_omp.h>
Public Member Functions | |
ParticleFilterOMPTracker (unsigned int nr_threads=0) | |
Initialize the scheduler and set the number of threads to use. More... | |
void | setNumberOfThreads (unsigned int nr_threads=0) |
Initialize the scheduler and set the number of threads to use. 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... | |
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 | weight () override |
weighting 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 actual computation. 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 | |
unsigned int | threads_ |
The number of threads the scheduler should use. More... | |
Protected Attributes inherited from pcl::tracking::ParticleFilterTracker< PointInT, StateT > | |
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... | |
ParticleFilterOMPTracker tracks the PointCloud which is given by setReferenceCloud within the measured PointCloud using particle filter method in parallel, using the OpenMP standard.
Definition at line 14 of file particle_filter_omp.h.
using pcl::tracking::ParticleFilterOMPTracker< PointInT, StateT >::BaseClass = Tracker<PointInT, StateT> |
Definition at line 38 of file particle_filter_omp.h.
using pcl::tracking::ParticleFilterOMPTracker< PointInT, StateT >::CloudCoherence = PointCloudCoherence<PointInT> |
Definition at line 52 of file particle_filter_omp.h.
using pcl::tracking::ParticleFilterOMPTracker< PointInT, StateT >::CloudCoherenceConstPtr = typename CloudCoherence::ConstPtr |
Definition at line 54 of file particle_filter_omp.h.
using pcl::tracking::ParticleFilterOMPTracker< PointInT, StateT >::CloudCoherencePtr = typename CloudCoherence::Ptr |
Definition at line 53 of file particle_filter_omp.h.
using pcl::tracking::ParticleFilterOMPTracker< PointInT, StateT >::Coherence = PointCoherence<PointInT> |
Definition at line 48 of file particle_filter_omp.h.
using pcl::tracking::ParticleFilterOMPTracker< PointInT, StateT >::CoherenceConstPtr = typename Coherence::ConstPtr |
Definition at line 50 of file particle_filter_omp.h.
using pcl::tracking::ParticleFilterOMPTracker< PointInT, StateT >::CoherencePtr = typename Coherence::Ptr |
Definition at line 49 of file particle_filter_omp.h.
using pcl::tracking::ParticleFilterOMPTracker< PointInT, StateT >::PointCloudIn = typename Tracker<PointInT, StateT>::PointCloudIn |
Definition at line 40 of file particle_filter_omp.h.
using pcl::tracking::ParticleFilterOMPTracker< PointInT, StateT >::PointCloudInConstPtr = typename PointCloudIn::ConstPtr |
Definition at line 42 of file particle_filter_omp.h.
using pcl::tracking::ParticleFilterOMPTracker< PointInT, StateT >::PointCloudInPtr = typename PointCloudIn::Ptr |
Definition at line 41 of file particle_filter_omp.h.
using pcl::tracking::ParticleFilterOMPTracker< PointInT, StateT >::PointCloudState = typename Tracker<PointInT, StateT>::PointCloudState |
Definition at line 44 of file particle_filter_omp.h.
using pcl::tracking::ParticleFilterOMPTracker< PointInT, StateT >::PointCloudStateConstPtr = typename PointCloudState::ConstPtr |
Definition at line 46 of file particle_filter_omp.h.
using pcl::tracking::ParticleFilterOMPTracker< PointInT, StateT >::PointCloudStatePtr = typename PointCloudState::Ptr |
Definition at line 45 of file particle_filter_omp.h.
|
inline |
Initialize the scheduler and set the number of threads to use.
nr_threads | the number of hardware threads to use (0 sets the value back to automatic) |
Definition at line 60 of file particle_filter_omp.h.
References pcl::tracking::ParticleFilterOMPTracker< PointInT, StateT >::setNumberOfThreads(), and pcl::tracking::Tracker< PointInT, StateT >::tracker_name_.
void pcl::tracking::ParticleFilterOMPTracker< PointInT, StateT >::setNumberOfThreads | ( | unsigned int | nr_threads = 0 | ) |
Initialize the scheduler and set the number of threads to use.
nr_threads | the number of hardware threads to use (0 sets the value back to automatic) |
Definition at line 11 of file particle_filter_omp.hpp.
Referenced by pcl::tracking::ParticleFilterOMPTracker< PointInT, StateT >::ParticleFilterOMPTracker().
|
overrideprotectedvirtual |
weighting phase of particle filter method.
calculate the likelihood of all of the particles and set the weights.
Reimplemented from pcl::tracking::ParticleFilterTracker< PointInT, StateT >.
Definition at line 26 of file particle_filter_omp.hpp.
|
protected |
The number of threads the scheduler should use.
Definition at line 77 of file particle_filter_omp.h.