Point Cloud Library (PCL)  1.9.1-dev
gicp.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010, 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 #pragma once
42 
43 #include <pcl/registration/icp.h>
44 #include <pcl/registration/bfgs.h>
45 
46 namespace pcl
47 {
48  /** \brief GeneralizedIterativeClosestPoint is an ICP variant that implements the
49  * generalized iterative closest point algorithm as described by Alex Segal et al. in
50  * http://www.robots.ox.ac.uk/~avsegal/resources/papers/Generalized_ICP.pdf
51  * The approach is based on using anistropic cost functions to optimize the alignment
52  * after closest point assignments have been made.
53  * The original code uses GSL and ANN while in ours we use an eigen mapped BFGS and
54  * FLANN.
55  * \author Nizar Sallem
56  * \ingroup registration
57  */
58  template <typename PointSource, typename PointTarget>
59  class GeneralizedIterativeClosestPoint : public IterativeClosestPoint<PointSource, PointTarget>
60  {
61  public:
80 
84 
88 
91 
92  using MatricesVector = std::vector< Eigen::Matrix3d, Eigen::aligned_allocator<Eigen::Matrix3d> >;
93  using MatricesVectorPtr = boost::shared_ptr<MatricesVector>;
94  using MatricesVectorConstPtr = boost::shared_ptr<const MatricesVector>;
95 
98 
99  using Ptr = boost::shared_ptr< GeneralizedIterativeClosestPoint<PointSource, PointTarget> >;
100  using ConstPtr = boost::shared_ptr< const GeneralizedIterativeClosestPoint<PointSource, PointTarget> >;
101 
102 
103  using Vector6d = Eigen::Matrix<double, 6, 1>;
104 
105  /** \brief Empty constructor. */
107  : k_correspondences_(20)
108  , gicp_epsilon_(0.001)
109  , rotation_epsilon_(2e-3)
110  , mahalanobis_(0)
112  {
114  reg_name_ = "GeneralizedIterativeClosestPoint";
115  max_iterations_ = 200;
118  rigid_transformation_estimation_ = [this] (const PointCloudSource& cloud_src,
119  const std::vector<int>& indices_src,
120  const PointCloudTarget& cloud_tgt,
121  const std::vector<int>& indices_tgt,
122  Eigen::Matrix4f& transformation_matrix)
123  {
124  estimateRigidTransformationBFGS (cloud_src, indices_src, cloud_tgt, indices_tgt, transformation_matrix);
125  };
126  }
127 
128  /** \brief Provide a pointer to the input dataset
129  * \param cloud the const boost shared pointer to a PointCloud message
130  */
131  inline void
132  setInputSource (const PointCloudSourceConstPtr &cloud) override
133  {
134 
135  if (cloud->points.empty ())
136  {
137  PCL_ERROR ("[pcl::%s::setInputSource] Invalid or empty point cloud dataset given!\n", getClassName ().c_str ());
138  return;
139  }
140  PointCloudSource input = *cloud;
141  // Set all the point.data[3] values to 1 to aid the rigid transformation
142  for (std::size_t i = 0; i < input.size (); ++i)
143  input[i].data[3] = 1.0;
144 
146  input_covariances_.reset ();
147  }
148 
149  /** \brief Provide a pointer to the covariances of the input source (if computed externally!).
150  * If not set, GeneralizedIterativeClosestPoint will compute the covariances itself.
151  * Make sure to set the covariances AFTER setting the input source point cloud (setting the input source point cloud will reset the covariances).
152  * \param[in] target the input point cloud target
153  */
154  inline void
156  {
157  input_covariances_ = covariances;
158  }
159 
160  /** \brief Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to)
161  * \param[in] target the input point cloud target
162  */
163  inline void
164  setInputTarget (const PointCloudTargetConstPtr &target) override
165  {
167  target_covariances_.reset ();
168  }
169 
170  /** \brief Provide a pointer to the covariances of the input target (if computed externally!).
171  * If not set, GeneralizedIterativeClosestPoint will compute the covariances itself.
172  * Make sure to set the covariances AFTER setting the input source point cloud (setting the input source point cloud will reset the covariances).
173  * \param[in] target the input point cloud target
174  */
175  inline void
177  {
178  target_covariances_ = covariances;
179  }
180 
181  /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using an iterative
182  * non-linear Levenberg-Marquardt approach.
183  * \param[in] cloud_src the source point cloud dataset
184  * \param[in] indices_src the vector of indices describing the points of interest in \a cloud_src
185  * \param[in] cloud_tgt the target point cloud dataset
186  * \param[in] indices_tgt the vector of indices describing the correspondences of the interest points from \a indices_src
187  * \param[out] transformation_matrix the resultant transformation matrix
188  */
189  void
191  const std::vector<int> &indices_src,
192  const PointCloudTarget &cloud_tgt,
193  const std::vector<int> &indices_tgt,
194  Eigen::Matrix4f &transformation_matrix);
195 
196  /** \brief \return Mahalanobis distance matrix for the given point index */
197  inline const Eigen::Matrix3d& mahalanobis(std::size_t index) const
198  {
199  assert(index < mahalanobis_.size());
200  return mahalanobis_[index];
201  }
202 
203  /** \brief Computes rotation matrix derivative.
204  * rotation matrix is obtainded from rotation angles x[3], x[4] and x[5]
205  * \return d/d_rx, d/d_ry and d/d_rz respectively in g[3], g[4] and g[5]
206  * param x array representing 3D transformation
207  * param R rotation matrix
208  * param g gradient vector
209  */
210  void
211  computeRDerivative(const Vector6d &x, const Eigen::Matrix3d &R, Vector6d &g) const;
212 
213  /** \brief Set the rotation epsilon (maximum allowable difference between two
214  * consecutive rotations) in order for an optimization to be considered as having
215  * converged to the final solution.
216  * \param epsilon the rotation epsilon
217  */
218  inline void
219  setRotationEpsilon (double epsilon) { rotation_epsilon_ = epsilon; }
220 
221  /** \brief Get the rotation epsilon (maximum allowable difference between two
222  * consecutive rotations) as set by the user.
223  */
224  inline double
226 
227  /** \brief Set the number of neighbors used when selecting a point neighbourhood
228  * to compute covariances.
229  * A higher value will bring more accurate covariance matrix but will make
230  * covariances computation slower.
231  * \param k the number of neighbors to use when computing covariances
232  */
233  void
235 
236  /** \brief Get the number of neighbors used when computing covariances as set by
237  * the user
238  */
239  int
241 
242  /** set maximum number of iterations at the optimization step
243  * \param[in] max maximum number of iterations for the optimizer
244  */
245  void
247 
248  ///\return maximum number of iterations at the optimization step
249  int
251 
252  protected:
253 
254  /** \brief The number of neighbors used for covariances computation.
255  * default: 20
256  */
258 
259  /** \brief The epsilon constant for gicp paper; this is NOT the convergence
260  * tolerance
261  * default: 0.001
262  */
264 
265  /** The epsilon constant for rotation error. (In GICP the transformation epsilon
266  * is split in rotation part and translation part).
267  * default: 2e-3
268  */
270 
271  /** \brief base transformation */
272  Eigen::Matrix4f base_transformation_;
273 
274  /** \brief Temporary pointer to the source dataset. */
276 
277  /** \brief Temporary pointer to the target dataset. */
279 
280  /** \brief Temporary pointer to the source dataset indices. */
281  const std::vector<int> *tmp_idx_src_;
282 
283  /** \brief Temporary pointer to the target dataset indices. */
284  const std::vector<int> *tmp_idx_tgt_;
285 
286 
287  /** \brief Input cloud points covariances. */
289 
290  /** \brief Target cloud points covariances. */
292 
293  /** \brief Mahalanobis matrices holder. */
294  std::vector<Eigen::Matrix3d> mahalanobis_;
295 
296  /** \brief maximum number of optimizations */
298 
299  /** \brief compute points covariances matrices according to the K nearest
300  * neighbors. K is set via setCorrespondenceRandomness() method.
301  * \param cloud pointer to point cloud
302  * \param tree KD tree performer for nearest neighbors search
303  * \param[out] cloud_covariances covariances matrices for each point in the cloud
304  */
305  template<typename PointT>
307  const typename pcl::search::KdTree<PointT>::Ptr tree,
308  MatricesVector& cloud_covariances);
309 
310  /** \return trace of mat1^t . mat2
311  * \param mat1 matrix of dimension nxm
312  * \param mat2 matrix of dimension nxp
313  */
314  inline double
315  matricesInnerProd(const Eigen::MatrixXd& mat1, const Eigen::MatrixXd& mat2) const
316  {
317  double r = 0.;
318  std::size_t n = mat1.rows();
319  // tr(mat1^t.mat2)
320  for(std::size_t i = 0; i < n; i++)
321  for(std::size_t j = 0; j < n; j++)
322  r += mat1 (j, i) * mat2 (i,j);
323  return r;
324  }
325 
326  /** \brief Rigid transformation computation method with initial guess.
327  * \param output the transformed input point cloud dataset using the rigid transformation found
328  * \param guess the initial guess of the transformation to compute
329  */
330  void
331  computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess) override;
332 
333  /** \brief Search for the closest nearest neighbor of a given point.
334  * \param query the point to search a nearest neighbour for
335  * \param index vector of size 1 to store the index of the nearest neighbour found
336  * \param distance vector of size 1 to store the distance to nearest neighbour found
337  */
338  inline bool
339  searchForNeighbors (const PointSource &query, std::vector<int>& index, std::vector<float>& distance)
340  {
341  int k = tree_->nearestKSearch (query, 1, index, distance);
342  if (k == 0)
343  return (false);
344  return (true);
345  }
346 
347  /// \brief compute transformation matrix from transformation matrix
348  void applyState(Eigen::Matrix4f &t, const Vector6d& x) const;
349 
350  /// \brief optimization functor structure
352  {
354  : BFGSDummyFunctor<double,6> (), gicp_(gicp) {}
355  double operator() (const Vector6d& x) override;
356  void df(const Vector6d &x, Vector6d &df) override;
357  void fdf(const Vector6d &x, double &f, Vector6d &df) override;
358 
360  };
361 
362  std::function<void(const pcl::PointCloud<PointSource> &cloud_src,
363  const std::vector<int> &src_indices,
364  const pcl::PointCloud<PointTarget> &cloud_tgt,
365  const std::vector<int> &tgt_indices,
366  Eigen::Matrix4f &transformation_matrix)> rigid_transformation_estimation_;
367  };
368 }
369 
370 #include <pcl/registration/impl/gicp.hpp>
Eigen::Matrix4f base_transformation_
base transformation
Definition: gicp.h:272
void setRotationEpsilon(double epsilon)
Set the rotation epsilon (maximum allowable difference between two consecutive rotations) in order fo...
Definition: gicp.h:219
void setTargetCovariances(const MatricesVectorPtr &covariances)
Provide a pointer to the covariances of the input target (if computed externally!).
Definition: gicp.h:176
const std::string & getClassName() const
Abstract class get name method.
Definition: registration.h:429
void estimateRigidTransformationBFGS(const PointCloudSource &cloud_src, const std::vector< int > &indices_src, const PointCloudTarget &cloud_tgt, const std::vector< int > &indices_tgt, Eigen::Matrix4f &transformation_matrix)
Estimate a rigid rotation transformation between a source and a target point cloud using an iterative...
Definition: gicp.hpp:181
GeneralizedIterativeClosestPoint()
Empty constructor.
Definition: gicp.h:106
std::vector< Eigen::Matrix3d > mahalanobis_
Mahalanobis matrices holder.
Definition: gicp.h:294
void setMaximumOptimizerIterations(int max)
set maximum number of iterations at the optimization step
Definition: gicp.h:246
std::function< void(const pcl::PointCloud< PointSource > &cloud_src, const std::vector< int > &src_indices, const pcl::PointCloud< PointTarget > &cloud_tgt, const std::vector< int > &tgt_indices, Eigen::Matrix4f &transformation_matrix)> rigid_transformation_estimation_
Definition: gicp.h:366
void df(const Vector6d &x, Vector6d &df) override
Definition: gicp.hpp:271
const std::vector< int > * tmp_idx_src_
Temporary pointer to the source dataset indices.
Definition: gicp.h:281
bool searchForNeighbors(const PointSource &query, std::vector< int > &index, std::vector< float > &distance)
Search for the closest nearest neighbor of a given point.
Definition: gicp.h:339
int max_inner_iterations_
maximum number of optimizations
Definition: gicp.h:297
This file defines compatibility wrappers for low level I/O functions.
Definition: convolution.h:45
const GeneralizedIterativeClosestPoint * gicp_
Definition: gicp.h:359
double matricesInnerProd(const Eigen::MatrixXd &mat1, const Eigen::MatrixXd &mat2) const
Definition: gicp.h:315
std::size_t size() const
Definition: point_cloud.h:432
void fdf(const Vector6d &x, double &f, Vector6d &df) override
Definition: gicp.hpp:307
void computeCovariances(typename pcl::PointCloud< PointT >::ConstPtr cloud, const typename pcl::search::KdTree< PointT >::Ptr tree, MatricesVector &cloud_covariances)
compute points covariances matrices according to the K nearest neighbors.
Definition: gicp.hpp:49
typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr
Definition: gicp.h:87
Eigen::Matrix< double, 6, 1 > Vector6d
Definition: gicp.h:103
const PointCloudSource * tmp_src_
Temporary pointer to the source dataset.
Definition: gicp.h:275
std::vector< Eigen::Matrix3d, Eigen::aligned_allocator< Eigen::Matrix3d > > MatricesVector
Definition: gicp.h:92
void setSourceCovariances(const MatricesVectorPtr &covariances)
Provide a pointer to the covariances of the input source (if computed externally!).
Definition: gicp.h:155
const std::vector< int > * tmp_idx_tgt_
Temporary pointer to the target dataset indices.
Definition: gicp.h:284
typename PointCloudSource::ConstPtr PointCloudSourceConstPtr
Definition: gicp.h:83
KdTreePtr tree_
A pointer to the spatial search object.
Definition: registration.h:492
int max_iterations_
The maximum number of iterations the internal optimization should run for.
Definition: registration.h:503
int k_correspondences_
The number of neighbors used for covariances computation.
Definition: gicp.h:257
double getRotationEpsilon()
Get the rotation epsilon (maximum allowable difference between two consecutive rotations) as set by t...
Definition: gicp.h:225
void setInputSource(const PointCloudSourceConstPtr &cloud) override
Provide a pointer to the input source (e.g., the point cloud that we want to align to the target) ...
Definition: icp.h:178
boost::shared_ptr< ::pcl::PointIndices > Ptr
Definition: PointIndices.h:22
typename PointCloudTarget::Ptr PointCloudTargetPtr
Definition: gicp.h:86
const PointCloudTarget * tmp_tgt_
Temporary pointer to the target dataset.
Definition: gicp.h:278
void applyState(Eigen::Matrix4f &t, const Vector6d &x) const
compute transformation matrix from transformation matrix
Definition: gicp.hpp:467
boost::shared_ptr< KdTree< PointT, Tree > > Ptr
Definition: kdtree.h:78
float distance(const PointT &p1, const PointT &p2)
Definition: geometry.h:60
typename PointCloudSource::Ptr PointCloudSourcePtr
Definition: gicp.h:82
boost::shared_ptr< const MatricesVector > MatricesVectorConstPtr
Definition: gicp.h:94
double gicp_epsilon_
The epsilon constant for gicp paper; this is NOT the convergence tolerance default: 0...
Definition: gicp.h:263
boost::shared_ptr< PointCloud< PointSource > > Ptr
Definition: point_cloud.h:412
IterativeClosestPoint provides a base implementation of the Iterative Closest Point algorithm...
Definition: icp.h:94
void setInputSource(const PointCloudSourceConstPtr &cloud) override
Provide a pointer to the input dataset.
Definition: gicp.h:132
int getCorrespondenceRandomness()
Get the number of neighbors used when computing covariances as set by the user.
Definition: gicp.h:240
boost::shared_ptr< const ::pcl::PointIndices > ConstPtr
Definition: PointIndices.h:23
Registration represents the base registration class for general purpose, ICP-like methods...
Definition: registration.h:60
PointCloud represents the base class in PCL for storing collections of 3D points. ...
boost::shared_ptr< GeneralizedIterativeClosestPoint< PointSource, PointTarget > > Ptr
Definition: gicp.h:99
void computeTransformation(PointCloudSource &output, const Eigen::Matrix4f &guess) override
Rigid transformation computation method with initial guess.
Definition: gicp.hpp:344
void setInputTarget(const PointCloudTargetConstPtr &cloud) override
Provide a pointer to the input target (e.g., the point cloud that we want to align to the target) ...
Definition: icp.h:212
boost::shared_ptr< MatricesVector > MatricesVectorPtr
Definition: gicp.h:93
double rotation_epsilon_
The epsilon constant for rotation error.
Definition: gicp.h:269
const Eigen::Matrix3d & mahalanobis(std::size_t index) const
Definition: gicp.h:197
PointIndices::Ptr PointIndicesPtr
Definition: gicp.h:89
boost::shared_ptr< const GeneralizedIterativeClosestPoint< PointSource, PointTarget > > ConstPtr
Definition: gicp.h:100
MatricesVectorPtr input_covariances_
Input cloud points covariances.
Definition: gicp.h:288
double transformation_epsilon_
The maximum difference between two consecutive transformations in order to consider convergence (user...
Definition: registration.h:523
boost::shared_ptr< const PointCloud< PointSource > > ConstPtr
Definition: point_cloud.h:413
void computeRDerivative(const Vector6d &x, const Eigen::Matrix3d &R, Vector6d &g) const
Computes rotation matrix derivative.
Definition: gicp.hpp:126
OptimizationFunctorWithIndices(const GeneralizedIterativeClosestPoint *gicp)
Definition: gicp.h:353
std::string reg_name_
The registration method name.
Definition: registration.h:489
double corr_dist_threshold_
The maximum distance threshold between two correspondent points in source <-> target.
Definition: registration.h:539
PointIndices::ConstPtr PointIndicesConstPtr
Definition: gicp.h:90
int min_number_correspondences_
The minimum number of correspondences that the algorithm needs before attempting to estimate the tran...
Definition: registration.h:553
void setInputTarget(const PointCloudTargetConstPtr &target) override
Provide a pointer to the input target (e.g., the point cloud that we want to align the input source t...
Definition: gicp.h:164
typename Registration< PointSource, PointTarget >::KdTree InputKdTree
Definition: gicp.h:96
typename Registration< PointSource, PointTarget >::KdTreePtr InputKdTreePtr
Definition: gicp.h:97
void setCorrespondenceRandomness(int k)
Set the number of neighbors used when selecting a point neighbourhood to compute covariances.
Definition: gicp.h:234
GeneralizedIterativeClosestPoint is an ICP variant that implements the generalized iterative closest ...
Definition: gicp.h:59
MatricesVectorPtr target_covariances_
Target cloud points covariances.
Definition: gicp.h:291