Point Cloud Library (PCL)  1.11.1-dev
ndt_2d.hpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2011-2012, Willow Garage, Inc.
6  * Copyright (c) 2012-, Open Perception, Inc.
7  *
8  * All rights reserved.
9  *
10  * Redistribution and use in source and binary forms, with or without
11  * modification, are permitted provided that the following conditions
12  * are met:
13  *
14  * * Redistributions of source code must retain the above copyright
15  * notice, this list of conditions and the following disclaimer.
16  * * Redistributions in binary form must reproduce the above
17  * copyright notice, this list of conditions and the following
18  * disclaimer in the documentation and/or other materials provided
19  * with the distribution.
20  * * Neither the name of the copyright holder(s) nor the names of its
21  * contributors may be used to endorse or promote products derived
22  * from this software without specific prior written permission.
23  *
24  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
25  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
26  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
27  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
28  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
29  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
30  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
32  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
33  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
34  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35  * POSSIBILITY OF SUCH DAMAGE.
36  *
37  * $Id$
38  *
39  */
40 
41 #ifndef PCL_NDT_2D_IMPL_H_
42 #define PCL_NDT_2D_IMPL_H_
43 
44 #include <Eigen/Eigenvalues> // for SelfAdjointEigenSolver, EigenSolver
45 
46 #include <cmath>
47 #include <memory>
48 
49 namespace pcl {
50 
51 namespace ndt2d {
52 /** \brief Class to store vector value and first and second derivatives
53  * (grad vector and hessian matrix), so they can be returned easily from
54  * functions
55  */
56 template <unsigned N = 3, typename T = double>
59 
60  Eigen::Matrix<T, N, N> hessian;
61  Eigen::Matrix<T, N, 1> grad;
62  T value;
63 
65  Zero()
66  {
68  r.hessian = Eigen::Matrix<T, N, N>::Zero();
69  r.grad = Eigen::Matrix<T, N, 1>::Zero();
70  r.value = 0;
71  return r;
72  }
73 
76  {
77  hessian += r.hessian;
78  grad += r.grad;
79  value += r.value;
80  return *this;
81  }
82 };
83 
84 /** \brief A normal distribution estimation class.
85  *
86  * First the indices of of the points from a point cloud that should be
87  * modelled by the distribution are added with addIdx (...).
88  *
89  * Then estimateParams (...) uses the stored point indices to estimate the
90  * parameters of a normal distribution, and discards the stored indices.
91  *
92  * Finally the distriubution, and its derivatives, may be evaluated at any
93  * point using test (...).
94  */
95 template <typename PointT>
96 class NormalDist {
98 
99 public:
100  NormalDist() : min_n_(3), n_(0) {}
101 
102  /** \brief Store a point index to use later for estimating distribution parameters.
103  * \param[in] i Point index to store
104  */
105  void
106  addIdx(std::size_t i)
107  {
108  pt_indices_.push_back(i);
109  }
110 
111  /** \brief Estimate the normal distribution parameters given the point indices
112  * provided. Memory of point indices is cleared. \param[in] cloud Point cloud
113  * corresponding to indices passed to addIdx. \param[in] min_covar_eigvalue_mult Set
114  * the smallest eigenvalue to this times the largest.
115  */
116  void
117  estimateParams(const PointCloud& cloud, double min_covar_eigvalue_mult = 0.001)
118  {
119  Eigen::Vector2d sx = Eigen::Vector2d::Zero();
120  Eigen::Matrix2d sxx = Eigen::Matrix2d::Zero();
121 
122  for (auto i = pt_indices_.cbegin(); i != pt_indices_.cend(); i++) {
123  Eigen::Vector2d p(cloud[*i].x, cloud[*i].y);
124  sx += p;
125  sxx += p * p.transpose();
126  }
127 
128  n_ = pt_indices_.size();
129 
130  if (n_ >= min_n_) {
131  mean_ = sx / static_cast<double>(n_);
132  // Using maximum likelihood estimation as in the original paper
133  Eigen::Matrix2d covar =
134  (sxx - 2 * (sx * mean_.transpose())) / static_cast<double>(n_) +
135  mean_ * mean_.transpose();
136 
137  Eigen::SelfAdjointEigenSolver<Eigen::Matrix2d> solver(covar);
138  if (solver.eigenvalues()[0] < min_covar_eigvalue_mult * solver.eigenvalues()[1]) {
139  PCL_DEBUG("[pcl::NormalDist::estimateParams] NDT normal fit: adjusting "
140  "eigenvalue %f\n",
141  solver.eigenvalues()[0]);
142  Eigen::Matrix2d l = solver.eigenvalues().asDiagonal();
143  Eigen::Matrix2d q = solver.eigenvectors();
144  // set minimum smallest eigenvalue:
145  l(0, 0) = l(1, 1) * min_covar_eigvalue_mult;
146  covar = q * l * q.transpose();
147  }
148  covar_inv_ = covar.inverse();
149  }
150 
151  pt_indices_.clear();
152  }
153 
154  /** \brief Return the 'score' (denormalised likelihood) and derivatives of score of
155  * the point p given this distribution. \param[in] transformed_pt Location to
156  * evaluate at. \param[in] cos_theta sin(theta) of the current rotation angle
157  * of rigid transformation: to avoid repeated evaluation \param[in] sin_theta
158  * cos(theta) of the current rotation angle of rigid transformation: to avoid repeated
159  * evaluation estimateParams must have been called after at least three points were
160  * provided, or this will return zero.
161  *
162  */
164  test(const PointT& transformed_pt,
165  const double& cos_theta,
166  const double& sin_theta) const
167  {
168  if (n_ < min_n_)
170 
172  const double x = transformed_pt.x;
173  const double y = transformed_pt.y;
174  const Eigen::Vector2d p_xy(transformed_pt.x, transformed_pt.y);
175  const Eigen::Vector2d q = p_xy - mean_;
176  const Eigen::RowVector2d qt_cvi(q.transpose() * covar_inv_);
177  const double exp_qt_cvi_q = std::exp(-0.5 * double(qt_cvi * q));
178  r.value = -exp_qt_cvi_q;
179 
180  Eigen::Matrix<double, 2, 3> jacobian;
181  jacobian << 1, 0, -(x * sin_theta + y * cos_theta), 0, 1,
182  x * cos_theta - y * sin_theta;
183 
184  for (std::size_t i = 0; i < 3; i++)
185  r.grad[i] = double(qt_cvi * jacobian.col(i)) * exp_qt_cvi_q;
186 
187  // second derivative only for i == j == 2:
188  const Eigen::Vector2d d2q_didj(y * sin_theta - x * cos_theta,
189  -(x * sin_theta + y * cos_theta));
190 
191  for (std::size_t i = 0; i < 3; i++)
192  for (std::size_t j = 0; j < 3; j++)
193  r.hessian(i, j) =
194  -exp_qt_cvi_q *
195  (double(-qt_cvi * jacobian.col(i)) * double(-qt_cvi * jacobian.col(j)) +
196  (-qt_cvi * ((i == 2 && j == 2) ? d2q_didj : Eigen::Vector2d::Zero())) +
197  (-jacobian.col(j).transpose() * covar_inv_ * jacobian.col(i)));
198 
199  return r;
200  }
201 
202 protected:
203  const std::size_t min_n_;
204 
205  std::size_t n_;
206  std::vector<std::size_t> pt_indices_;
207  Eigen::Vector2d mean_;
208  Eigen::Matrix2d covar_inv_;
209 };
210 
211 /** \brief Build a set of normal distributions modelling a 2D point cloud,
212  * and provide the value and derivatives of the model at any point via the
213  * test (...) function.
214  */
215 template <typename PointT>
216 class NDTSingleGrid : public boost::noncopyable {
218  using PointCloudConstPtr = typename PointCloud::ConstPtr;
220 
221 public:
222  NDTSingleGrid(PointCloudConstPtr cloud,
223  const Eigen::Vector2f& about,
224  const Eigen::Vector2f& extent,
225  const Eigen::Vector2f& step)
226  : min_(about - extent)
227  , max_(min_ + 2 * extent)
228  , step_(step)
229  , cells_((max_[0] - min_[0]) / step_[0], (max_[1] - min_[1]) / step_[1])
231  {
232  // sort through all points, assigning them to distributions:
233  std::size_t used_points = 0;
234  for (std::size_t i = 0; i < cloud->size(); i++)
235  if (NormalDist* n = normalDistForPoint(cloud->at(i))) {
236  n->addIdx(i);
237  used_points++;
238  }
239 
240  PCL_DEBUG("[pcl::NDTSingleGrid] NDT single grid %dx%d using %d/%d points\n",
241  cells_[0],
242  cells_[1],
243  used_points,
244  cloud->size());
245 
246  // then bake the distributions such that they approximate the
247  // points (and throw away memory of the points)
248  for (int x = 0; x < cells_[0]; x++)
249  for (int y = 0; y < cells_[1]; y++)
250  normal_distributions_.coeffRef(x, y).estimateParams(*cloud);
251  }
252 
253  /** \brief Return the 'score' (denormalised likelihood) and derivatives of score of
254  * the point p given this distribution. \param[in] transformed_pt Location to
255  * evaluate at. \param[in] cos_theta sin(theta) of the current rotation angle
256  * of rigid transformation: to avoid repeated evaluation \param[in] sin_theta
257  * cos(theta) of the current rotation angle of rigid transformation: to avoid repeated
258  * evaluation
259  */
261  test(const PointT& transformed_pt,
262  const double& cos_theta,
263  const double& sin_theta) const
264  {
265  const NormalDist* n = normalDistForPoint(transformed_pt);
266  // index is in grid, return score from the normal distribution from
267  // the correct part of the grid:
268  if (n)
269  return n->test(transformed_pt, cos_theta, sin_theta);
271  }
272 
273 protected:
274  /** \brief Return the normal distribution covering the location of point p
275  * \param[in] p a point
276  */
277  NormalDist*
278  normalDistForPoint(PointT const& p) const
279  {
280  // this would be neater in 3d...
281  Eigen::Vector2f idxf;
282  for (std::size_t i = 0; i < 2; i++)
283  idxf[i] = (p.getVector3fMap()[i] - min_[i]) / step_[i];
284  Eigen::Vector2i idxi = idxf.cast<int>();
285  for (std::size_t i = 0; i < 2; i++)
286  if (idxi[i] >= cells_[i] || idxi[i] < 0)
287  return nullptr;
288  // const cast to avoid duplicating this function in const and
289  // non-const variants...
290  return const_cast<NormalDist*>(&normal_distributions_.coeffRef(idxi[0], idxi[1]));
291  }
292 
293  Eigen::Vector2f min_;
294  Eigen::Vector2f max_;
295  Eigen::Vector2f step_;
296  Eigen::Vector2i cells_;
297 
298  Eigen::Matrix<NormalDist, Eigen::Dynamic, Eigen::Dynamic> normal_distributions_;
299 };
300 
301 /** \brief Build a Normal Distributions Transform of a 2D point cloud. This
302  * consists of the sum of four overlapping models of the original points
303  * with normal distributions.
304  * The value and derivatives of the model at any point can be evaluated
305  * with the test (...) function.
306  */
307 template <typename PointT>
308 class NDT2D : public boost::noncopyable {
310  using PointCloudConstPtr = typename PointCloud::ConstPtr;
312 
313 public:
314  /** \brief
315  * \param[in] cloud the input point cloud
316  * \param[in] about Centre of the grid for normal distributions model
317  * \param[in] extent Extent of grid for normal distributions model
318  * \param[in] step Size of region that each normal distribution will model
319  */
320  NDT2D(PointCloudConstPtr cloud,
321  const Eigen::Vector2f& about,
322  const Eigen::Vector2f& extent,
323  const Eigen::Vector2f& step)
324  {
325  Eigen::Vector2f dx(step[0] / 2, 0);
326  Eigen::Vector2f dy(0, step[1] / 2);
327  single_grids_[0].reset(new SingleGrid(cloud, about, extent, step));
328  single_grids_[1].reset(new SingleGrid(cloud, about + dx, extent, step));
329  single_grids_[2].reset(new SingleGrid(cloud, about + dy, extent, step));
330  single_grids_[3].reset(new SingleGrid(cloud, about + dx + dy, extent, step));
331  }
332 
333  /** \brief Return the 'score' (denormalised likelihood) and derivatives of score of
334  * the point p given this distribution. \param[in] transformed_pt Location to
335  * evaluate at. \param[in] cos_theta sin(theta) of the current rotation angle
336  * of rigid transformation: to avoid repeated evaluation \param[in] sin_theta
337  * cos(theta) of the current rotation angle of rigid transformation: to avoid repeated
338  * evaluation
339  */
341  test(const PointT& transformed_pt,
342  const double& cos_theta,
343  const double& sin_theta) const
344  {
346  for (const auto& single_grid : single_grids_)
347  r += single_grid->test(transformed_pt, cos_theta, sin_theta);
348  return r;
349  }
350 
351 protected:
352  std::shared_ptr<SingleGrid> single_grids_[4];
353 };
354 
355 } // namespace ndt2d
356 } // namespace pcl
357 
358 namespace Eigen {
359 
360 /* This NumTraits specialisation is necessary because NormalDist is used as
361  * the element type of an Eigen Matrix.
362  */
363 template <typename PointT>
364 struct NumTraits<pcl::ndt2d::NormalDist<PointT>> {
365  using Real = double;
366  using Literal = double;
367  static Real
369  {
370  return 1.0;
371  }
372  enum {
373  IsComplex = 0,
374  IsInteger = 0,
375  IsSigned = 0,
376  RequireInitialization = 1,
377  ReadCost = 1,
378  AddCost = 1,
379  MulCost = 1
380  };
381 };
382 
383 } // namespace Eigen
384 
385 namespace pcl {
386 
387 template <typename PointSource, typename PointTarget>
388 void
390  PointCloudSource& output, const Eigen::Matrix4f& guess)
391 {
392  PointCloudSource intm_cloud = output;
393 
394  nr_iterations_ = 0;
395  converged_ = false;
396 
397  if (guess != Eigen::Matrix4f::Identity()) {
398  transformation_ = guess;
399  transformPointCloud(output, intm_cloud, transformation_);
400  }
401 
402  // build Normal Distribution Transform of target cloud:
403  ndt2d::NDT2D<PointTarget> target_ndt(target_, grid_centre_, grid_extent_, grid_step_);
404 
405  // can't seem to use .block<> () member function on transformation_
406  // directly... gcc bug?
407  Eigen::Matrix4f& transformation = transformation_;
408 
409  // work with x translation, y translation and z rotation: extending to 3D
410  // would be some tricky maths, but not impossible.
411  const Eigen::Matrix3f initial_rot(transformation.block<3, 3>(0, 0));
412  const Eigen::Vector3f rot_x(initial_rot * Eigen::Vector3f::UnitX());
413  const double z_rotation = std::atan2(rot_x[1], rot_x[0]);
414 
415  Eigen::Vector3d xytheta_transformation(
416  transformation(0, 3), transformation(1, 3), z_rotation);
417 
418  while (!converged_) {
419  const double cos_theta = std::cos(xytheta_transformation[2]);
420  const double sin_theta = std::sin(xytheta_transformation[2]);
421  previous_transformation_ = transformation;
422 
425  for (std::size_t i = 0; i < intm_cloud.size(); i++)
426  score += target_ndt.test(intm_cloud[i], cos_theta, sin_theta);
427 
428  PCL_DEBUG("[pcl::NormalDistributionsTransform2D::computeTransformation] NDT score "
429  "%f (x=%f,y=%f,r=%f)\n",
430  float(score.value),
431  xytheta_transformation[0],
432  xytheta_transformation[1],
433  xytheta_transformation[2]);
434 
435  if (score.value != 0) {
436  // test for positive definiteness, and adjust to ensure it if necessary:
437  Eigen::EigenSolver<Eigen::Matrix3d> solver;
438  solver.compute(score.hessian, false);
439  double min_eigenvalue = 0;
440  for (int i = 0; i < 3; i++)
441  if (solver.eigenvalues()[i].real() < min_eigenvalue)
442  min_eigenvalue = solver.eigenvalues()[i].real();
443 
444  // ensure "safe" positive definiteness: this is a detail missing
445  // from the original paper
446  if (min_eigenvalue < 0) {
447  double lambda = 1.1 * min_eigenvalue - 1;
448  score.hessian += Eigen::Vector3d(-lambda, -lambda, -lambda).asDiagonal();
449  solver.compute(score.hessian, false);
450  PCL_DEBUG("[pcl::NormalDistributionsTransform2D::computeTransformation] adjust "
451  "hessian: %f: new eigenvalues:%f %f %f\n",
452  float(lambda),
453  solver.eigenvalues()[0].real(),
454  solver.eigenvalues()[1].real(),
455  solver.eigenvalues()[2].real());
456  }
457  assert(solver.eigenvalues()[0].real() >= 0 &&
458  solver.eigenvalues()[1].real() >= 0 &&
459  solver.eigenvalues()[2].real() >= 0);
460 
461  Eigen::Vector3d delta_transformation(-score.hessian.inverse() * score.grad);
462  Eigen::Vector3d new_transformation =
463  xytheta_transformation + newton_lambda_.cwiseProduct(delta_transformation);
464 
465  xytheta_transformation = new_transformation;
466 
467  // update transformation matrix from x, y, theta:
468  transformation.block<3, 3>(0, 0).matrix() = Eigen::Matrix3f(Eigen::AngleAxisf(
469  static_cast<float>(xytheta_transformation[2]), Eigen::Vector3f::UnitZ()));
470  transformation.block<3, 1>(0, 3).matrix() =
471  Eigen::Vector3f(static_cast<float>(xytheta_transformation[0]),
472  static_cast<float>(xytheta_transformation[1]),
473  0.0f);
474 
475  // std::cout << "new transformation:\n" << transformation << std::endl;
476  }
477  else {
478  PCL_ERROR("[pcl::NormalDistributionsTransform2D::computeTransformation] no "
479  "overlap: try increasing the size or reducing the step of the grid\n");
480  break;
481  }
482 
483  transformPointCloud(output, intm_cloud, transformation);
484 
485  nr_iterations_++;
486 
487  if (update_visualizer_)
488  update_visualizer_(output, *indices_, *target_, *indices_);
489 
490  // std::cout << "eps=" << std::abs ((transformation - previous_transformation_).sum
491  // ()) << std::endl;
492 
493  Eigen::Matrix4f transformation_delta =
494  transformation.inverse() * previous_transformation_;
495  double cos_angle =
496  0.5 * (transformation_delta.coeff(0, 0) + transformation_delta.coeff(1, 1) +
497  transformation_delta.coeff(2, 2) - 1);
498  double translation_sqr =
499  transformation_delta.coeff(0, 3) * transformation_delta.coeff(0, 3) +
500  transformation_delta.coeff(1, 3) * transformation_delta.coeff(1, 3) +
501  transformation_delta.coeff(2, 3) * transformation_delta.coeff(2, 3);
502 
503  if (nr_iterations_ >= max_iterations_ ||
504  ((transformation_epsilon_ > 0 && translation_sqr <= transformation_epsilon_) &&
505  (transformation_rotation_epsilon_ > 0 &&
506  cos_angle >= transformation_rotation_epsilon_)) ||
507  ((transformation_epsilon_ <= 0) &&
508  (transformation_rotation_epsilon_ > 0 &&
509  cos_angle >= transformation_rotation_epsilon_)) ||
510  ((transformation_epsilon_ > 0 && translation_sqr <= transformation_epsilon_) &&
511  (transformation_rotation_epsilon_ <= 0))) {
512  converged_ = true;
513  }
514  }
515  final_transformation_ = transformation;
516  output = intm_cloud;
517 }
518 
519 } // namespace pcl
520 
521 #endif // PCL_NDT_2D_IMPL_H_
pcl::ndt2d::ValueAndDerivatives
Class to store vector value and first and second derivatives (grad vector and hessian matrix),...
Definition: ndt_2d.hpp:57
pcl::ndt2d::ValueAndDerivatives::Zero
static ValueAndDerivatives< N, T > Zero()
Definition: ndt_2d.hpp:65
pcl
Definition: convolution.h:46
pcl::ndt2d::ValueAndDerivatives::value
T value
Definition: ndt_2d.hpp:62
pcl::ndt2d::NormalDist::addIdx
void addIdx(std::size_t i)
Store a point index to use later for estimating distribution parameters.
Definition: ndt_2d.hpp:106
Eigen
Definition: bfgs.h:10
pcl::ndt2d::NormalDist::covar_inv_
Eigen::Matrix2d covar_inv_
Definition: ndt_2d.hpp:208
pcl::ndt2d::NormalDist
A normal distribution estimation class.
Definition: ndt_2d.hpp:96
pcl::ndt2d::ValueAndDerivatives::ValueAndDerivatives
ValueAndDerivatives()
Definition: ndt_2d.hpp:58
pcl::ndt2d::NDT2D::test
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 distr...
Definition: ndt_2d.hpp:341
pcl::ndt2d::NDTSingleGrid::normalDistForPoint
NormalDist * normalDistForPoint(PointT const &p) const
Return the normal distribution covering the location of point p.
Definition: ndt_2d.hpp:278
pcl::ndt2d::NDTSingleGrid::normal_distributions_
Eigen::Matrix< NormalDist, Eigen::Dynamic, Eigen::Dynamic > normal_distributions_
Definition: ndt_2d.hpp:298
pcl::PointCloud
PointCloud represents the base class in PCL for storing collections of 3D points.
Definition: distances.h:55
Eigen::NumTraits< pcl::ndt2d::NormalDist< PointT > >::dummy_precision
static Real dummy_precision()
Definition: ndt_2d.hpp:368
pcl::NormalDistributionsTransform2D::computeTransformation
void computeTransformation(PointCloudSource &output, const Eigen::Matrix4f &guess) override
Rigid transformation computation method with initial guess.
Definition: ndt_2d.hpp:389
pcl::PointXYZRGB
A point structure representing Euclidean xyz coordinates, and the RGB color.
Definition: point_types.hpp:630
pcl::ndt2d::NDT2D::NDT2D
NDT2D(PointCloudConstPtr cloud, const Eigen::Vector2f &about, const Eigen::Vector2f &extent, const Eigen::Vector2f &step)
Definition: ndt_2d.hpp:320
pcl::transformPointCloud
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.
Definition: transforms.hpp:221
pcl::ndt2d::NormalDist::n_
std::size_t n_
Definition: ndt_2d.hpp:205
pcl::ndt2d::NDTSingleGrid::cells_
Eigen::Vector2i cells_
Definition: ndt_2d.hpp:296
pcl::ndt2d::NDTSingleGrid::min_
Eigen::Vector2f min_
Definition: ndt_2d.hpp:293
pcl::ndt2d::ValueAndDerivatives::operator+=
ValueAndDerivatives< N, T > & operator+=(ValueAndDerivatives< N, T > const &r)
Definition: ndt_2d.hpp:75
Eigen::NumTraits< pcl::ndt2d::NormalDist< PointT > >::Real
double Real
Definition: ndt_2d.hpp:365
pcl::ndt2d::NDTSingleGrid
Build a set of normal distributions modelling a 2D point cloud, and provide the value and derivatives...
Definition: ndt_2d.hpp:216
pcl::ndt2d::NDT2D::single_grids_
std::shared_ptr< SingleGrid > single_grids_[4]
Definition: ndt_2d.hpp:352
pcl::ndt2d::NDTSingleGrid::step_
Eigen::Vector2f step_
Definition: ndt_2d.hpp:295
pcl::ndt2d::NormalDist::min_n_
const std::size_t min_n_
Definition: ndt_2d.hpp:203
Eigen::NumTraits< pcl::ndt2d::NormalDist< PointT > >::Literal
double Literal
Definition: ndt_2d.hpp:366
pcl::ndt2d::NDTSingleGrid::NDTSingleGrid
NDTSingleGrid(PointCloudConstPtr cloud, const Eigen::Vector2f &about, const Eigen::Vector2f &extent, const Eigen::Vector2f &step)
Definition: ndt_2d.hpp:222
pcl::ndt2d::ValueAndDerivatives::grad
Eigen::Matrix< T, N, 1 > grad
Definition: ndt_2d.hpp:61
pcl::ndt2d::NDTSingleGrid::max_
Eigen::Vector2f max_
Definition: ndt_2d.hpp:294
pcl::ndt2d::NormalDist::mean_
Eigen::Vector2d mean_
Definition: ndt_2d.hpp:207
pcl::ndt2d::NormalDist::pt_indices_
std::vector< std::size_t > pt_indices_
Definition: ndt_2d.hpp:206
pcl::PointCloud::ConstPtr
shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:408
pcl::ndt2d::NormalDist::NormalDist
NormalDist()
Definition: ndt_2d.hpp:100
pcl::ndt2d::NormalDist::estimateParams
void estimateParams(const PointCloud &cloud, double min_covar_eigvalue_mult=0.001)
Estimate the normal distribution parameters given the point indices provided.
Definition: ndt_2d.hpp:117
pcl::ndt2d::NormalDist::test
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 distr...
Definition: ndt_2d.hpp:164
pcl::ndt2d::ValueAndDerivatives::hessian
Eigen::Matrix< T, N, N > hessian
Definition: ndt_2d.hpp:60
pcl::ndt2d::NDTSingleGrid::test
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 distr...
Definition: ndt_2d.hpp:261
pcl::ndt2d::NDT2D
Build a Normal Distributions Transform of a 2D point cloud.
Definition: ndt_2d.hpp:308