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