Build a set of normal distributions modelling a 2D point cloud, and provide the value and derivatives of the model at any point via the test (...) function. More...
#include <ndt_2d.hpp>
Public Member Functions | |
NDTSingleGrid (PointCloudConstPtr cloud, const Eigen::Vector2f &about, const Eigen::Vector2f &extent, const Eigen::Vector2f &step) | |
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 Member Functions | |
NormalDist * | normalDistForPoint (PointT const &p) const |
Return the normal distribution covering the location of point p. | |
Protected Attributes | |
Eigen::Vector2i | cells_ |
Eigen::Vector2f | max_ |
Eigen::Vector2f | min_ |
Eigen::Matrix< NormalDist, Eigen::Dynamic, Eigen::Dynamic > | normal_distributions_ |
Eigen::Vector2f | step_ |
Private Types | |
typedef pcl::ndt2d::NormalDist < PointT > | NormalDist |
typedef pcl::PointCloud< PointT > | PointCloud |
typedef pcl::PointCloud < PointT >::ConstPtr | PointCloudConstPtr |
Build a set of normal distributions modelling a 2D point cloud, and provide the value and derivatives of the model at any point via the test (...) function.
Definition at line 218 of file ndt_2d.hpp.
typedef pcl::ndt2d::NormalDist<PointT> pcl::ndt2d::NDTSingleGrid< PointT >::NormalDist [private] |
Definition at line 222 of file ndt_2d.hpp.
typedef pcl::PointCloud<PointT> pcl::ndt2d::NDTSingleGrid< PointT >::PointCloud [private] |
Definition at line 220 of file ndt_2d.hpp.
typedef pcl::PointCloud<PointT>::ConstPtr pcl::ndt2d::NDTSingleGrid< PointT >::PointCloudConstPtr [private] |
Definition at line 221 of file ndt_2d.hpp.
pcl::ndt2d::NDTSingleGrid< PointT >::NDTSingleGrid | ( | PointCloudConstPtr | cloud, |
const Eigen::Vector2f & | about, | ||
const Eigen::Vector2f & | extent, | ||
const Eigen::Vector2f & | step | ||
) | [inline] |
Definition at line 225 of file ndt_2d.hpp.
NormalDist* pcl::ndt2d::NDTSingleGrid< PointT >::normalDistForPoint | ( | PointT const & | p | ) | const [inline, protected] |
Return the normal distribution covering the location of point p.
[in] | p | a point |
Definition at line 275 of file ndt_2d.hpp.
ValueAndDerivatives<3,double> pcl::ndt2d::NDTSingleGrid< 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 |
Definition at line 259 of file ndt_2d.hpp.
Eigen::Vector2i pcl::ndt2d::NDTSingleGrid< PointT >::cells_ [protected] |
Definition at line 293 of file ndt_2d.hpp.
Eigen::Vector2f pcl::ndt2d::NDTSingleGrid< PointT >::max_ [protected] |
Definition at line 291 of file ndt_2d.hpp.
Eigen::Vector2f pcl::ndt2d::NDTSingleGrid< PointT >::min_ [protected] |
Definition at line 290 of file ndt_2d.hpp.
Eigen::Matrix<NormalDist, Eigen::Dynamic, Eigen::Dynamic> pcl::ndt2d::NDTSingleGrid< PointT >::normal_distributions_ [protected] |
Definition at line 295 of file ndt_2d.hpp.
Eigen::Vector2f pcl::ndt2d::NDTSingleGrid< PointT >::step_ [protected] |
Definition at line 292 of file ndt_2d.hpp.