1#ifndef PCL_TRACKING_IMPL_PARTICLE_FILTER_H_
2#define PCL_TRACKING_IMPL_PARTICLE_FILTER_H_
5#include <pcl/common/transforms.h>
6#include <pcl/tracking/particle_filter.h>
12template <
typename Po
intInT,
typename StateT>
17 PCL_ERROR(
"[pcl::%s::initCompute] Init failed.\n",
getClassName().c_str());
40template <
typename Po
intInT,
typename StateT>
43 const std::vector<int>& a,
const std::vector<double>& q)
45 static std::mt19937 rng{std::random_device{}()};
46 std::uniform_real_distribution<> rd(0.0, 1.0);
48 double rU = rd(rng) *
static_cast<double>(
particles_->size());
49 int k =
static_cast<int>(rU);
56template <
typename Po
intInT,
typename StateT>
60 std::vector<double>& q,
64 std::vector<int> HL(particles->size());
66 auto L = HL.end() - 1;
67 const auto num = particles->size();
68 for (std::size_t i = 0; i < num; i++)
69 q[i] = (*particles)[i].weight *
static_cast<float>(num);
70 for (std::size_t i = 0; i < num; i++)
71 a[i] =
static_cast<int>(i);
73 for (std::size_t i = 0; i < num; i++)
75 *H++ =
static_cast<int>(i);
77 *L-- =
static_cast<int>(i);
79 while (H != HL.begin() && L != HL.end() - 1) {
92template <
typename Po
intInT,
typename StateT>
99 StateT offset = StateT::toState(
trans_);
115template <
typename Po
intInT,
typename StateT>
120 double w_min = std::numeric_limits<double>::max();
121 double w_max = -std::numeric_limits<double>::max();
123 double weight = point.weight;
131 if (w_max != w_min) {
133 if (point.weight != 0.0) {
141 point.weight = 1.0f /
static_cast<float>(
particles_->size());
151 point.weight /=
static_cast<float>(sum);
155 point.weight = 1.0f /
static_cast<float>(
particles_->size());
160template <
typename Po
intInT,
typename StateT>
165 double x_min, y_min, z_min, x_max, y_max, z_max;
167 pass_x_.setFilterLimits(
static_cast<float>(x_min),
static_cast<float>(x_max));
168 pass_y_.setFilterLimits(
static_cast<float>(y_min),
static_cast<float>(y_max));
169 pass_z_.setFilterLimits(
static_cast<float>(z_min),
static_cast<float>(z_max));
185template <
typename Po
intInT,
typename StateT>
194 x_min = y_min = z_min = std::numeric_limits<double>::max();
195 x_max = y_max = z_max = -std::numeric_limits<double>::max();
216template <
typename Po
intInT,
typename StateT>
227 return !newPointIdxVector.empty();
230template <
typename Po
intInT,
typename StateT>
235 for (std::size_t i = 0; i <
particles_->size(); i++) {
245 for (std::size_t i = 0; i <
particles_->size(); i++) {
252 for (std::size_t i = 0; i <
particles_->size(); i++) {
263 for (std::size_t i = 0; i <
particles_->size(); i++) {
273template <
typename Po
intInT,
typename StateT>
284template <
typename Po
intInT,
typename StateT>
295template <
typename Po
intInT,
typename StateT>
296template <
typename Po
intT, pcl::traits::HasNormal<Po
intT>>
304 for (std::size_t i = 0; i < cloud.size(); i++) {
305 PointInT input_point = cloud[i];
307 if (!std::isfinite(input_point.x) || !std::isfinite(input_point.y) ||
308 !std::isfinite(input_point.z))
311 Eigen::Vector4f p = input_point.getVector4fMap();
312 Eigen::Vector4f n = input_point.getNormalVector4fMap();
315 indices.push_back(i);
319template <
typename Po
intInT,
typename StateT>
326template <
typename Po
intInT,
typename StateT>
334 const std::vector<double> zero_mean(StateT::stateDimension(), 0.0);
345 for (
int i = 1; i < motion_num; i++) {
347 StateT p = (*origparticles)[target_particle_index];
357 StateT p = (*origparticles)[target_particle_index];
364template <
typename Po
intInT,
typename StateT>
377template <
typename Po
intInT,
typename StateT>
403#define PCL_INSTANTIATE_ParticleFilterTracker(T, ST) \
404 template class PCL_EXPORTS pcl::tracking::ParticleFilterTracker<T, ST>;
PointCloudConstPtr input_
Octree pointcloud change detector class
void genAliasTable(std::vector< int > &a, std::vector< double > &q, const PointCloudStateConstPtr &particles)
Generate the tables for walker's alias method.
int iteration_num_
The number of iteration of particlefilter.
double motion_ratio_
Ratio of hypothesis to use motion model.
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.
void initParticles(bool reset)
Initialize the particles.
CloudCoherencePtr coherence_
A pointer to PointCloudCoherence.
int sampleWithReplacement(const std::vector< int > &a, const std::vector< double > &q)
Implementation of "sample with replacement" using Walker's alias method.
bool testChangeDetection(const PointCloudInConstPtr &input)
Run change detection and return true if there is a change.
PointCloudInConstPtr ref_
A pointer to reference point cloud.
typename PointCloudIn::ConstPtr PointCloudInConstPtr
void computeTransformedPointCloud(const StateT &hypothesis, pcl::Indices &indices, PointCloudIn &cloud)
Compute a reference pointcloud transformed to the pose that hypothesis represents.
std::vector< double > initial_noise_covariance_
The diagonal elements of covariance matrix of the initial noise.
void computeTransformedPointCloudWithNormal(const StateT &hypothesis, pcl::Indices &indices, PointCloudIn &cloud)
Compute a reference pointcloud transformed to the pose that hypothesis represents and calculate indic...
void resampleWithReplacement()
Resampling the particle with replacement.
Eigen::Affine3f toEigenMatrix(const StateT &particle)
Convert a state to affine transformation from the world coordinates frame.
bool changed_
A flag to be true when change of pointclouds is detected.
StateT representative_state_
The result of tracking.
unsigned int change_detector_filter_
Minimum points in a leaf when calling change detector.
pcl::octree::OctreePointCloudChangeDetector< PointInT >::Ptr change_detector_
Change detector used as a trigger to track.
typename PointCloudState::Ptr PointCloudStatePtr
double change_detector_resolution_
Resolution of change detector.
std::vector< double > step_noise_covariance_
The diagonal elements of covariance matrix of the step noise.
pcl::PassThrough< PointInT > pass_z_
Pass through filter to crop the pointclouds within the hypothesis bounding box.
std::vector< PointCloudInPtr > transed_reference_vector_
A list of the pointers to pointclouds.
void computeTransformedPointCloudWithoutNormal(const StateT &hypothesis, PointCloudIn &cloud)
Compute a reference pointcloud transformed to the pose that hypothesis represents and calculate indic...
virtual void resample()
Resampling phase of particle filter method.
typename PointCloudState::ConstPtr PointCloudStateConstPtr
pcl::PassThrough< PointInT > pass_y_
Pass through filter to crop the pointclouds within the hypothesis bounding box.
std::vector< double > initial_noise_mean_
The mean values of initial noise.
void computeTracking() override
Track the pointcloud using particle filter method.
bool use_normal_
A flag to use normal or not.
void cropInputPointCloud(const PointCloudInConstPtr &cloud, PointCloudIn &output)
Crop the pointcloud by the bounding box calculated from hypothesis and the reference pointcloud.
PointCloudStatePtr particles_
A pointer to the particles.
double fit_ratio_
Adjustment of the particle filter.
double normalizeParticleWeight(double w, double w_min, double w_max)
Normalize the weight of a particle using .
virtual void update()
Calculate the weighted mean of the particles and set it as the result.
int particle_num_
The number of the particles.
virtual void weight()
Weighting phase of particle filter method.
pcl::PassThrough< PointInT > pass_x_
Pass through filter to crop the pointclouds within the hypothesis bounding box.
bool initCompute() override
This method should get called before starting the actual computation.
typename PointCloudIn::Ptr PointCloudInPtr
typename Tracker< PointInT, StateT >::PointCloudState PointCloudState
StateT motion_
Difference between the result in t and t-1.
typename Tracker< PointInT, StateT >::PointCloudIn PointCloudIn
Eigen::Affine3f trans_
An affine transformation from the world coordinates frame to the origin of the particles.
virtual void normalizeWeight()
Normalize the weights of all the particels.
double occlusion_angle_thr_
The threshold for the points to be considered as occluded.
const std::string & getClassName() const
Get a string representation of the name of this class.
virtual bool initCompute()
This method should get called before starting the actual computation.
Define standard C methods and C++ classes that are common to all methods.
void transformPointCloudWithNormals(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 4, 4 > &transform, bool copy_all_fields)
Transform a point cloud and rotate its normals using an Eigen transform.
void getMinMax3D(const pcl::PointCloud< PointT > &cloud, PointT &min_pt, PointT &max_pt)
Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud.
double getAngle3D(const Eigen::Vector4f &v1, const Eigen::Vector4f &v2, const bool in_degree=false)
Compute the smallest angle between two 3D vectors in radians (default) or degree.
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 4, 4 > &transform, bool copy_all_fields)
Apply a rigid transform defined by a 4x4 matrix.
shared_ptr< Indices > IndicesPtr
IndicesAllocator<> Indices
Type used for indices in PCL.