A normal distribution estimation class. More...
#include <ndt_2d.hpp>
Public Member Functions | |
void | addIdx (size_t i) |
Store a point index to use later for estimating distribution parameters. | |
void | estimateParams (const PointCloud &cloud, double min_covar_eigvalue_mult=0.001) |
Estimate the normal distribution parameters given the point indices provided. Memory of point indices is cleared. | |
NormalDist () | |
ValueAndDerivatives< 3, double > | test (const PointT &transformed_pt, const double &cos_theta, const double &sin_theta) const |
Return the 'score' (denormalised likelihood) and derivatives of score of the point p given this distribution. | |
Protected Attributes | |
Eigen::Matrix2d | covar_inv_ |
Eigen::Vector2d | mean_ |
const size_t | min_n_ |
size_t | n_ |
std::vector< size_t > | pt_indices_ |
Private Types | |
typedef pcl::PointCloud< PointT > | PointCloud |
A normal distribution estimation class.
First the indices of of the points from a point cloud that should be modelled by the distribution are added with addIdx (...).
Then estimateParams (...) uses the stored point indices to estimate the parameters of a normal distribution, and discards the stored indices.
Finally the distriubution, and its derivatives, may be evaluated at any point using test (...).
Definition at line 96 of file ndt_2d.hpp.
typedef pcl::PointCloud<PointT> pcl::ndt2d::NormalDist< PointT >::PointCloud [private] |
Definition at line 98 of file ndt_2d.hpp.
pcl::ndt2d::NormalDist< PointT >::NormalDist | ( | ) | [inline] |
Definition at line 101 of file ndt_2d.hpp.
void pcl::ndt2d::NormalDist< PointT >::addIdx | ( | size_t | i | ) | [inline] |
Store a point index to use later for estimating distribution parameters.
[in] | i | Point index to store |
Definition at line 110 of file ndt_2d.hpp.
void pcl::ndt2d::NormalDist< PointT >::estimateParams | ( | const PointCloud & | cloud, |
double | min_covar_eigvalue_mult = 0.001 |
||
) | [inline] |
Estimate the normal distribution parameters given the point indices provided. Memory of point indices is cleared.
[in] | cloud | Point cloud corresponding to indices passed to addIdx. |
[in] | min_covar_eigvalue_mult | Set the smallest eigenvalue to this times the largest. |
Definition at line 120 of file ndt_2d.hpp.
ValueAndDerivatives<3,double> pcl::ndt2d::NormalDist< PointT >::test | ( | const PointT & | transformed_pt, |
const double & | cos_theta, | ||
const double & | sin_theta | ||
) | const [inline] |
Return the 'score' (denormalised likelihood) and derivatives of score of the point p given this distribution.
[in] | transformed_pt | Location to evaluate at. |
[in] | cos_theta | sin(theta) of the current rotation angle of rigid transformation: to avoid repeated evaluation |
[in] | sin_theta | cos(theta) of the current rotation angle of rigid transformation: to avoid repeated evaluation estimateParams must have been called after at least three points were provided, or this will return zero. |
Definition at line 165 of file ndt_2d.hpp.
Eigen::Matrix2d pcl::ndt2d::NormalDist< PointT >::covar_inv_ [protected] |
Definition at line 210 of file ndt_2d.hpp.
Eigen::Vector2d pcl::ndt2d::NormalDist< PointT >::mean_ [protected] |
Definition at line 209 of file ndt_2d.hpp.
const size_t pcl::ndt2d::NormalDist< PointT >::min_n_ [protected] |
Definition at line 205 of file ndt_2d.hpp.
size_t pcl::ndt2d::NormalDist< PointT >::n_ [protected] |
Definition at line 207 of file ndt_2d.hpp.
std::vector<size_t> pcl::ndt2d::NormalDist< PointT >::pt_indices_ [protected] |
Definition at line 208 of file ndt_2d.hpp.