Point Cloud Library (PCL)  1.7.1
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 #ifndef PCL_NDT_2D_IMPL_H_
41 #define PCL_NDT_2D_IMPL_H_
42 #include <cmath>
43 
44 #include <pcl/registration/eigen.h>
45 #include <pcl/registration/boost.h>
46 
47 namespace pcl
48 {
49  namespace ndt2d
50  {
51  /** \brief Class to store vector value and first and second derivatives
52  * (grad vector and hessian matrix), so they can be returned easily from
53  * functions
54  */
55  template<unsigned N=3, typename T=double>
57  {
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
97  {
99 
100  public:
102  : min_n_ (3), n_ (0), pt_indices_ (), mean_ (), covar_inv_ ()
103  {
104  }
105 
106  /** \brief Store a point index to use later for estimating distribution parameters.
107  * \param[in] i Point index to store
108  */
109  void
110  addIdx (size_t i)
111  {
112  pt_indices_.push_back (i);
113  }
114 
115  /** \brief Estimate the normal distribution parameters given the point indices provided. Memory of point indices is cleared.
116  * \param[in] cloud Point cloud corresponding to indices passed to addIdx.
117  * \param[in] min_covar_eigvalue_mult Set the smallest eigenvalue to this times the largest.
118  */
119  void
120  estimateParams (const PointCloud& cloud, double min_covar_eigvalue_mult = 0.001)
121  {
122  Eigen::Vector2d sx = Eigen::Vector2d::Zero ();
123  Eigen::Matrix2d sxx = Eigen::Matrix2d::Zero ();
124 
125  std::vector<size_t>::const_iterator i;
126  for (i = pt_indices_.begin (); i != pt_indices_.end (); i++)
127  {
128  Eigen::Vector2d p (cloud[*i]. x, cloud[*i]. y);
129  sx += p;
130  sxx += p * p.transpose ();
131  }
132 
133  n_ = pt_indices_.size ();
134 
135  if (n_ >= min_n_)
136  {
137  mean_ = sx / static_cast<double> (n_);
138  // Using maximum likelihood estimation as in the original paper
139  Eigen::Matrix2d covar = (sxx - 2 * (sx * mean_.transpose ())) / static_cast<double> (n_) + mean_ * mean_.transpose ();
140 
141  Eigen::SelfAdjointEigenSolver<Eigen::Matrix2d> solver (covar);
142  if (solver.eigenvalues ()[0] < min_covar_eigvalue_mult * solver.eigenvalues ()[1])
143  {
144  PCL_DEBUG ("[pcl::NormalDist::estimateParams] NDT normal fit: adjusting eigenvalue %f\n", solver.eigenvalues ()[0]);
145  Eigen::Matrix2d l = solver.eigenvalues ().asDiagonal ();
146  Eigen::Matrix2d q = solver.eigenvectors ();
147  // set minimum smallest eigenvalue:
148  l (0,0) = l (1,1) * min_covar_eigvalue_mult;
149  covar = q * l * q.transpose ();
150  }
151  covar_inv_ = covar.inverse ();
152  }
153 
154  pt_indices_.clear ();
155  }
156 
157  /** \brief Return the 'score' (denormalised likelihood) and derivatives of score of the point p given this distribution.
158  * \param[in] transformed_pt Location to evaluate at.
159  * \param[in] cos_theta sin(theta) of the current rotation angle of rigid transformation: to avoid repeated evaluation
160  * \param[in] sin_theta cos(theta) of the current rotation angle of rigid transformation: to avoid repeated evaluation
161  * estimateParams must have been called after at least three points were provided, or this will return zero.
162  *
163  */
165  test (const PointT& transformed_pt, const double& cos_theta, const double& sin_theta) const
166  {
167  if (n_ < min_n_)
169 
171  const double x = transformed_pt.x;
172  const double y = transformed_pt.y;
173  const Eigen::Vector2d p_xy (transformed_pt.x, transformed_pt.y);
174  const Eigen::Vector2d q = p_xy - mean_;
175  const Eigen::RowVector2d qt_cvi (q.transpose () * covar_inv_);
176  const double exp_qt_cvi_q = std::exp (-0.5 * double (qt_cvi * q));
177  r.value = -exp_qt_cvi_q;
178 
179  Eigen::Matrix<double, 2, 3> jacobian;
180  jacobian <<
181  1, 0, -(x * sin_theta + y*cos_theta),
182  0, 1, x * cos_theta - y*sin_theta;
183 
184  for (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 (
189  y * sin_theta - x*cos_theta,
190  -(x * sin_theta + y*cos_theta)
191  );
192 
193  for (size_t i = 0; i < 3; i++)
194  for (size_t j = 0; j < 3; j++)
195  r.hessian (i,j) = -exp_qt_cvi_q * (
196  double (-qt_cvi*jacobian.col (i)) * double (-qt_cvi*jacobian.col (j)) +
197  (-qt_cvi * ((i==2 && j==2)? d2q_didj : Eigen::Vector2d::Zero ())) +
198  (-jacobian.col (j).transpose () * covar_inv_ * jacobian.col (i))
199  );
200 
201  return r;
202  }
203 
204  protected:
205  const size_t min_n_;
206 
207  size_t n_;
208  std::vector<size_t> pt_indices_;
209  Eigen::Vector2d mean_;
210  Eigen::Matrix2d covar_inv_;
211  };
212 
213  /** \brief Build a set of normal distributions modelling a 2D point cloud,
214  * and provide the value and derivatives of the model at any point via the
215  * test (...) function.
216  */
217  template <typename PointT>
218  class NDTSingleGrid: public boost::noncopyable
219  {
220  typedef typename pcl::PointCloud<PointT> PointCloud;
221  typedef typename pcl::PointCloud<PointT>::ConstPtr PointCloudConstPtr;
223 
224  public:
225  NDTSingleGrid (PointCloudConstPtr cloud,
226  const Eigen::Vector2f& about,
227  const Eigen::Vector2f& extent,
228  const Eigen::Vector2f& step)
229  : min_ (about - extent), max_ (min_ + 2*extent), step_ (step),
230  cells_ ((max_[0]-min_[0]) / step_[0],
231  (max_[1]-min_[1]) / step_[1]),
233  {
234  // sort through all points, assigning them to distributions:
235  NormalDist* n;
236  size_t used_points = 0;
237  for (size_t i = 0; i < cloud->size (); i++)
238  if ((n = normalDistForPoint (cloud->at (i))))
239  {
240  n->addIdx (i);
241  used_points++;
242  }
243 
244  PCL_DEBUG ("[pcl::NDTSingleGrid] NDT single grid %dx%d using %d/%d points\n", cells_[0], cells_[1], used_points, 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 the point p given this distribution.
254  * \param[in] transformed_pt Location to evaluate at.
255  * \param[in] cos_theta sin(theta) of the current rotation angle of rigid transformation: to avoid repeated evaluation
256  * \param[in] sin_theta cos(theta) of the current rotation angle of rigid transformation: to avoid repeated evaluation
257  */
259  test (const PointT& transformed_pt, const double& cos_theta, const double& sin_theta) const
260  {
261  const NormalDist* n = normalDistForPoint (transformed_pt);
262  // index is in grid, return score from the normal distribution from
263  // the correct part of the grid:
264  if (n)
265  return n->test (transformed_pt, cos_theta, sin_theta);
266  else
268  }
269 
270  protected:
271  /** \brief Return the normal distribution covering the location of point p
272  * \param[in] p a point
273  */
274  NormalDist*
275  normalDistForPoint (PointT const& p) const
276  {
277  // this would be neater in 3d...
278  Eigen::Vector2f idxf;
279  for (size_t i = 0; i < 2; i++)
280  idxf[i] = (p.getVector3fMap ()[i] - min_[i]) / step_[i];
281  Eigen::Vector2i idxi = idxf.cast<int> ();
282  for (size_t i = 0; i < 2; i++)
283  if (idxi[i] >= cells_[i] || idxi[i] < 0)
284  return NULL;
285  // const cast to avoid duplicating this function in const and
286  // non-const variants...
287  return const_cast<NormalDist*> (&normal_distributions_.coeffRef (idxi[0], idxi[1]));
288  }
289 
290  Eigen::Vector2f min_;
291  Eigen::Vector2f max_;
292  Eigen::Vector2f step_;
293  Eigen::Vector2i cells_;
294 
295  Eigen::Matrix<NormalDist, Eigen::Dynamic, Eigen::Dynamic> normal_distributions_;
296  };
297 
298  /** \brief Build a Normal Distributions Transform of a 2D point cloud. This
299  * consists of the sum of four overlapping models of the original points
300  * with normal distributions.
301  * The value and derivatives of the model at any point can be evaluated
302  * with the test (...) function.
303  */
304  template <typename PointT>
305  class NDT2D: public boost::noncopyable
306  {
307  typedef typename pcl::PointCloud<PointT> PointCloud;
308  typedef typename pcl::PointCloud<PointT>::ConstPtr PointCloudConstPtr;
310 
311  public:
312  /** \brief
313  * \param[in] cloud the input point cloud
314  * \param[in] about Centre of the grid for normal distributions model
315  * \param[in] extent Extent of grid for normal distributions model
316  * \param[in] step Size of region that each normal distribution will model
317  */
318  NDT2D (PointCloudConstPtr cloud,
319  const Eigen::Vector2f& about,
320  const Eigen::Vector2f& extent,
321  const Eigen::Vector2f& step)
322  {
323  Eigen::Vector2f dx (step[0]/2, 0);
324  Eigen::Vector2f dy (0, step[1]/2);
325  single_grids_[0] = boost::make_shared<SingleGrid> (cloud, about, extent, step);
326  single_grids_[1] = boost::make_shared<SingleGrid> (cloud, about +dx, extent, step);
327  single_grids_[2] = boost::make_shared<SingleGrid> (cloud, about +dy, extent, step);
328  single_grids_[3] = boost::make_shared<SingleGrid> (cloud, about +dx+dy, extent, step);
329  }
330 
331  /** \brief Return the 'score' (denormalised likelihood) and derivatives of score of the point p given this distribution.
332  * \param[in] transformed_pt Location to evaluate at.
333  * \param[in] cos_theta sin(theta) of the current rotation angle of rigid transformation: to avoid repeated evaluation
334  * \param[in] sin_theta cos(theta) of the current rotation angle of rigid transformation: to avoid repeated evaluation
335  */
337  test (const PointT& transformed_pt, const double& cos_theta, const double& sin_theta) const
338  {
340  for (size_t i = 0; i < 4; i++)
341  r += single_grids_[i]->test (transformed_pt, cos_theta, sin_theta);
342  return r;
343  }
344 
345  protected:
346  boost::shared_ptr<SingleGrid> single_grids_[4];
347  };
348 
349  } // namespace ndt2d
350 } // namespace pcl
351 
352 
353 namespace Eigen
354 {
355  /* This NumTraits specialisation is necessary because NormalDist is used as
356  * the element type of an Eigen Matrix.
357  */
358  template<typename PointT> struct NumTraits<pcl::ndt2d::NormalDist<PointT> >
359  {
360  typedef double Real;
361  static Real dummy_precision () { return 1.0; }
362  enum {
363  IsComplex = 0,
364  IsInteger = 0,
365  IsSigned = 0,
366  RequireInitialization = 1,
367  ReadCost = 1,
368  AddCost = 1,
369  MulCost = 1
370  };
371  };
372 }
373 
374 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////
375 template <typename PointSource, typename PointTarget> void
376 pcl::NormalDistributionsTransform2D<PointSource, PointTarget>::computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess)
377 {
378  PointCloudSource intm_cloud = output;
379 
380  if (guess != Eigen::Matrix4f::Identity ())
381  {
382  transformation_ = guess;
383  transformPointCloud (output, intm_cloud, transformation_);
384  }
385 
386  // build Normal Distribution Transform of target cloud:
387  ndt2d::NDT2D<PointTarget> target_ndt (target_, grid_centre_, grid_extent_, grid_step_);
388 
389  // can't seem to use .block<> () member function on transformation_
390  // directly... gcc bug?
391  Eigen::Matrix4f& transformation = transformation_;
392 
393 
394  // work with x translation, y translation and z rotation: extending to 3D
395  // would be some tricky maths, but not impossible.
396  const Eigen::Matrix3f initial_rot (transformation.block<3,3> (0,0));
397  const Eigen::Vector3f rot_x (initial_rot*Eigen::Vector3f::UnitX ());
398  const double z_rotation = std::atan2 (rot_x[1], rot_x[0]);
399 
400  Eigen::Vector3d xytheta_transformation (
401  transformation (0,3),
402  transformation (1,3),
403  z_rotation
404  );
405 
406  while (!converged_)
407  {
408  const double cos_theta = std::cos (xytheta_transformation[2]);
409  const double sin_theta = std::sin (xytheta_transformation[2]);
410  previous_transformation_ = transformation;
411 
413  for (size_t i = 0; i < intm_cloud.size (); i++)
414  score += target_ndt.test (intm_cloud[i], cos_theta, sin_theta);
415 
416  PCL_DEBUG ("[pcl::NormalDistributionsTransform2D::computeTransformation] NDT score %f (x=%f,y=%f,r=%f)\n",
417  float (score.value), xytheta_transformation[0], xytheta_transformation[1], xytheta_transformation[2]
418  );
419 
420  if (score.value != 0)
421  {
422  // test for positive definiteness, and adjust to ensure it if necessary:
423  Eigen::EigenSolver<Eigen::Matrix3d> solver;
424  solver.compute (score.hessian, false);
425  double min_eigenvalue = 0;
426  for (int i = 0; i <3; i++)
427  if (solver.eigenvalues ()[i].real () < min_eigenvalue)
428  min_eigenvalue = solver.eigenvalues ()[i].real ();
429 
430  // ensure "safe" positive definiteness: this is a detail missing
431  // from the original paper
432  if (min_eigenvalue < 0)
433  {
434  double lambda = 1.1 * min_eigenvalue - 1;
435  score.hessian += Eigen::Vector3d (-lambda, -lambda, -lambda).asDiagonal ();
436  solver.compute (score.hessian, false);
437  PCL_DEBUG ("[pcl::NormalDistributionsTransform2D::computeTransformation] adjust hessian: %f: new eigenvalues:%f %f %f\n",
438  float (lambda),
439  solver.eigenvalues ()[0].real (),
440  solver.eigenvalues ()[1].real (),
441  solver.eigenvalues ()[2].real ()
442  );
443  }
444  assert (solver.eigenvalues ()[0].real () >= 0 &&
445  solver.eigenvalues ()[1].real () >= 0 &&
446  solver.eigenvalues ()[2].real () >= 0);
447 
448  Eigen::Vector3d delta_transformation (-score.hessian.inverse () * score.grad);
449  Eigen::Vector3d new_transformation = xytheta_transformation + newton_lambda_.cwiseProduct (delta_transformation);
450 
451  xytheta_transformation = new_transformation;
452 
453  // update transformation matrix from x, y, theta:
454  transformation.block<3,3> (0,0).matrix () = Eigen::Matrix3f (Eigen::AngleAxisf (static_cast<float> (xytheta_transformation[2]), Eigen::Vector3f::UnitZ ()));
455  transformation.block<3,1> (0,3).matrix () = Eigen::Vector3f (static_cast<float> (xytheta_transformation[0]), static_cast<float> (xytheta_transformation[1]), 0.0f);
456 
457  //std::cout << "new transformation:\n" << transformation << std::endl;
458  }
459  else
460  {
461  PCL_ERROR ("[pcl::NormalDistributionsTransform2D::computeTransformation] no overlap: try increasing the size or reducing the step of the grid\n");
462  break;
463  }
464 
465  transformPointCloud (output, intm_cloud, transformation);
466 
467  nr_iterations_++;
468 
469  if (update_visualizer_ != 0)
470  update_visualizer_ (output, *indices_, *target_, *indices_);
471 
472  //std::cout << "eps=" << fabs ((transformation - previous_transformation_).sum ()) << std::endl;
473 
474  if (nr_iterations_ > max_iterations_ ||
475  (transformation - previous_transformation_).array ().abs ().sum () < transformation_epsilon_)
476  converged_ = true;
477  }
478  final_transformation_ = transformation;
479  output = intm_cloud;
480 }
481 
482 #endif // PCL_NDT_2D_IMPL_H_
483 
Build a set of normal distributions modelling a 2D point cloud, and provide the value and derivatives...
Definition: ndt_2d.hpp:218
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:165
virtual void computeTransformation(PointCloudSource &output, const Eigen::Matrix4f &guess)
Rigid transformation computation method with initial guess.
Definition: ndt_2d.hpp:376
void addIdx(size_t i)
Store a point index to use later for estimating distribution parameters.
Definition: ndt_2d.hpp:110
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:259
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:337
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Transform< Scalar, 3, Eigen::Affine > &transform)
Apply an affine transform defined by an Eigen Transform.
Definition: transforms.hpp:42
NDT2D(PointCloudConstPtr cloud, const Eigen::Vector2f &about, const Eigen::Vector2f &extent, const Eigen::Vector2f &step)
Definition: ndt_2d.hpp:318
Eigen::Matrix< T, N, N > hessian
Definition: ndt_2d.hpp:60
boost::shared_ptr< SingleGrid > single_grids_[4]
Definition: ndt_2d.hpp:346
Class to store vector value and first and second derivatives (grad vector and hessian matrix)...
Definition: ndt_2d.hpp:56
Eigen::Vector2f max_
Definition: ndt_2d.hpp:291
std::vector< size_t > pt_indices_
Definition: ndt_2d.hpp:208
Definition: bfgs.h:10
Build a Normal Distributions Transform of a 2D point cloud.
Definition: ndt_2d.hpp:305
boost::shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:429
Eigen::Vector2d mean_
Definition: ndt_2d.hpp:209
Eigen::Matrix2d covar_inv_
Definition: ndt_2d.hpp:210
NDTSingleGrid(PointCloudConstPtr cloud, const Eigen::Vector2f &about, const Eigen::Vector2f &extent, const Eigen::Vector2f &step)
Definition: ndt_2d.hpp:225
ValueAndDerivatives< N, T > & operator+=(ValueAndDerivatives< N, T > const &r)
Definition: ndt_2d.hpp:75
Eigen::Matrix< NormalDist, Eigen::Dynamic, Eigen::Dynamic > normal_distributions_
Definition: ndt_2d.hpp:295
Eigen::Matrix< T, N, 1 > grad
Definition: ndt_2d.hpp:61
Eigen::Vector2i cells_
Definition: ndt_2d.hpp:293
NormalDist * normalDistForPoint(PointT const &p) const
Return the normal distribution covering the location of point p.
Definition: ndt_2d.hpp:275
const size_t min_n_
Definition: ndt_2d.hpp:205
A point structure representing Euclidean xyz coordinates, and the RGB color.
static ValueAndDerivatives< N, T > Zero()
Definition: ndt_2d.hpp:65
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:120
Eigen::Vector2f min_
Definition: ndt_2d.hpp:290
PointCloud represents the base class in PCL for storing collections of 3D points. ...
Eigen::Vector2f step_
Definition: ndt_2d.hpp:292
A normal distribution estimation class.
Definition: ndt_2d.hpp:96