Point Cloud Library (PCL)  1.7.2
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.stanford.edu/~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 
95 
96  typedef boost::shared_ptr< GeneralizedIterativeClosestPoint<PointSource, PointTarget> > Ptr;
97  typedef boost::shared_ptr< const GeneralizedIterativeClosestPoint<PointSource, PointTarget> > ConstPtr;
98 
99 
100  typedef Eigen::Matrix<double, 6, 1> Vector6d;
101 
102  /** \brief Empty constructor. */
104  : k_correspondences_(20)
105  , gicp_epsilon_(0.001)
106  , rotation_epsilon_(2e-3)
107  , input_covariances_(0)
109  , mahalanobis_(0)
111  {
113  reg_name_ = "GeneralizedIterativeClosestPoint";
114  max_iterations_ = 200;
119  this, _1, _2, _3, _4, _5);
120  }
121 
122  /** \brief Provide a pointer to the input dataset
123  * \param cloud the const boost shared pointer to a PointCloud message
124  */
125  PCL_DEPRECATED ("[pcl::registration::GeneralizedIterativeClosestPoint::setInputCloud] setInputCloud is deprecated. Please use setInputSource instead.")
126  void
127  setInputCloud (const PointCloudSourceConstPtr &cloud);
128 
129  /** \brief Provide a pointer to the input dataset
130  * \param cloud the const boost shared pointer to a PointCloud message
131  */
132  inline void
133  setInputSource (const PointCloudSourceConstPtr &cloud)
134  {
135 
136  if (cloud->points.empty ())
137  {
138  PCL_ERROR ("[pcl::%s::setInputSource] Invalid or empty point cloud dataset given!\n", getClassName ().c_str ());
139  return;
140  }
141  PointCloudSource input = *cloud;
142  // Set all the point.data[3] values to 1 to aid the rigid transformation
143  for (size_t i = 0; i < input.size (); ++i)
144  input[i].data[3] = 1.0;
145 
147  input_covariances_.clear ();
148  input_covariances_.reserve (input_->size ());
149  }
150 
151  /** \brief Provide a pointer to the input target (e.g., the point cloud that we want to align the input source to)
152  * \param[in] target the input point cloud target
153  */
154  inline void
155  setInputTarget (const PointCloudTargetConstPtr &target)
156  {
158  target_covariances_.clear ();
159  target_covariances_.reserve (target_->size ());
160  }
161 
162  /** \brief Estimate a rigid rotation transformation between a source and a target point cloud using an iterative
163  * non-linear Levenberg-Marquardt approach.
164  * \param[in] cloud_src the source point cloud dataset
165  * \param[in] indices_src the vector of indices describing the points of interest in \a cloud_src
166  * \param[in] cloud_tgt the target point cloud dataset
167  * \param[in] indices_tgt the vector of indices describing the correspondences of the interst points from \a indices_src
168  * \param[out] transformation_matrix the resultant transformation matrix
169  */
170  void
171  estimateRigidTransformationBFGS (const PointCloudSource &cloud_src,
172  const std::vector<int> &indices_src,
173  const PointCloudTarget &cloud_tgt,
174  const std::vector<int> &indices_tgt,
175  Eigen::Matrix4f &transformation_matrix);
176 
177  /** \brief \return Mahalanobis distance matrix for the given point index */
178  inline const Eigen::Matrix3d& mahalanobis(size_t index) const
179  {
180  assert(index < mahalanobis_.size());
181  return mahalanobis_[index];
182  }
183 
184  /** \brief Computes rotation matrix derivative.
185  * rotation matrix is obtainded from rotation angles x[3], x[4] and x[5]
186  * \return d/d_rx, d/d_ry and d/d_rz respectively in g[3], g[4] and g[5]
187  * param x array representing 3D transformation
188  * param R rotation matrix
189  * param g gradient vector
190  */
191  void
192  computeRDerivative(const Vector6d &x, const Eigen::Matrix3d &R, Vector6d &g) const;
193 
194  /** \brief Set the rotation epsilon (maximum allowable difference between two
195  * consecutive rotations) in order for an optimization to be considered as having
196  * converged to the final solution.
197  * \param epsilon the rotation epsilon
198  */
199  inline void
200  setRotationEpsilon (double epsilon) { rotation_epsilon_ = epsilon; }
201 
202  /** \brief Get the rotation epsilon (maximum allowable difference between two
203  * consecutive rotations) as set by the user.
204  */
205  inline double
207 
208  /** \brief Set the number of neighbors used when selecting a point neighbourhood
209  * to compute covariances.
210  * A higher value will bring more accurate covariance matrix but will make
211  * covariances computation slower.
212  * \param k the number of neighbors to use when computing covariances
213  */
214  void
216 
217  /** \brief Get the number of neighbors used when computing covariances as set by
218  * the user
219  */
220  int
222 
223  /** set maximum number of iterations at the optimization step
224  * \param[in] max maximum number of iterations for the optimizer
225  */
226  void
228 
229  ///\return maximum number of iterations at the optimization step
230  int
232 
233  protected:
234 
235  /** \brief The number of neighbors used for covariances computation.
236  * default: 20
237  */
239 
240  /** \brief The epsilon constant for gicp paper; this is NOT the convergence
241  * tolerence
242  * default: 0.001
243  */
245 
246  /** The epsilon constant for rotation error. (In GICP the transformation epsilon
247  * is split in rotation part and translation part).
248  * default: 2e-3
249  */
251 
252  /** \brief base transformation */
253  Eigen::Matrix4f base_transformation_;
254 
255  /** \brief Temporary pointer to the source dataset. */
256  const PointCloudSource *tmp_src_;
257 
258  /** \brief Temporary pointer to the target dataset. */
259  const PointCloudTarget *tmp_tgt_;
260 
261  /** \brief Temporary pointer to the source dataset indices. */
262  const std::vector<int> *tmp_idx_src_;
263 
264  /** \brief Temporary pointer to the target dataset indices. */
265  const std::vector<int> *tmp_idx_tgt_;
266 
267 
268  /** \brief Input cloud points covariances. */
269  std::vector<Eigen::Matrix3d> input_covariances_;
270 
271  /** \brief Target cloud points covariances. */
272  std::vector<Eigen::Matrix3d> target_covariances_;
273 
274  /** \brief Mahalanobis matrices holder. */
275  std::vector<Eigen::Matrix3d> mahalanobis_;
276 
277  /** \brief maximum number of optimizations */
279 
280  /** \brief compute points covariances matrices according to the K nearest
281  * neighbors. K is set via setCorrespondenceRandomness() methode.
282  * \param cloud pointer to point cloud
283  * \param tree KD tree performer for nearest neighbors search
284  * \param[out] cloud_covariances covariances matrices for each point in the cloud
285  */
286  template<typename PointT>
288  const typename pcl::search::KdTree<PointT>::Ptr tree,
289  std::vector<Eigen::Matrix3d>& cloud_covariances);
290 
291  /** \return trace of mat1^t . mat2
292  * \param mat1 matrix of dimension nxm
293  * \param mat2 matrix of dimension nxp
294  */
295  inline double
296  matricesInnerProd(const Eigen::MatrixXd& mat1, const Eigen::MatrixXd& mat2) const
297  {
298  double r = 0.;
299  size_t n = mat1.rows();
300  // tr(mat1^t.mat2)
301  for(size_t i = 0; i < n; i++)
302  for(size_t j = 0; j < n; j++)
303  r += mat1 (j, i) * mat2 (i,j);
304  return r;
305  }
306 
307  /** \brief Rigid transformation computation method with initial guess.
308  * \param output the transformed input point cloud dataset using the rigid transformation found
309  * \param guess the initial guess of the transformation to compute
310  */
311  void
312  computeTransformation (PointCloudSource &output, const Eigen::Matrix4f &guess);
313 
314  /** \brief Search for the closest nearest neighbor of a given point.
315  * \param query the point to search a nearest neighbour for
316  * \param index vector of size 1 to store the index of the nearest neighbour found
317  * \param distance vector of size 1 to store the distance to nearest neighbour found
318  */
319  inline bool
320  searchForNeighbors (const PointSource &query, std::vector<int>& index, std::vector<float>& distance)
321  {
322  int k = tree_->nearestKSearch (query, 1, index, distance);
323  if (k == 0)
324  return (false);
325  return (true);
326  }
327 
328  /// \brief compute transformation matrix from transformation matrix
329  void applyState(Eigen::Matrix4f &t, const Vector6d& x) const;
330 
331  /// \brief optimization functor structure
333  {
335  : BFGSDummyFunctor<double,6> (), gicp_(gicp) {}
336  double operator() (const Vector6d& x);
337  void df(const Vector6d &x, Vector6d &df);
338  void fdf(const Vector6d &x, double &f, Vector6d &df);
339 
341  };
342 
343  boost::function<void(const pcl::PointCloud<PointSource> &cloud_src,
344  const std::vector<int> &src_indices,
345  const pcl::PointCloud<PointTarget> &cloud_tgt,
346  const std::vector<int> &tgt_indices,
347  Eigen::Matrix4f &transformation_matrix)> rigid_transformation_estimation_;
348  };
349 }
350 
351 #include <pcl/registration/impl/gicp.hpp>
352 
353 #endif //#ifndef PCL_GICP_H_
Eigen::Matrix4f base_transformation_
base transformation
Definition: gicp.h:253
void setRotationEpsilon(double epsilon)
Set the rotation epsilon (maximum allowable difference between two consecutive rotations) in order fo...
Definition: gicp.h:200
PointIndices::Ptr PointIndicesPtr
Definition: gicp.h:90
boost::shared_ptr< PointCloud< PointSource > > Ptr
Definition: point_cloud.h:428
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:213
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:347
GeneralizedIterativeClosestPoint()
Empty constructor.
Definition: gicp.h:103
std::vector< Eigen::Matrix3d > mahalanobis_
Mahalanobis matrices holder.
Definition: gicp.h:275
void setMaximumOptimizerIterations(int max)
set maximum number of iterations at the optimization step
Definition: gicp.h:227
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:155
Registration< PointSource, PointTarget >::KdTree InputKdTree
Definition: gicp.h:93
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:262
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:320
int max_inner_iterations_
maximum number of optimizations
Definition: gicp.h:278
const GeneralizedIterativeClosestPoint * gicp_
Definition: gicp.h:340
void computeCovariances(typename pcl::PointCloud< PointT >::ConstPtr cloud, const typename pcl::search::KdTree< PointT >::Ptr tree, std::vector< Eigen::Matrix3d > &cloud_covariances)
compute points covariances matrices according to the K nearest neighbors.
Definition: gicp.hpp:57
size_t size() const
Definition: point_cloud.h:440
void fdf(const Vector6d &x, double &f, Vector6d &df)
Definition: gicp.hpp:316
const PointCloudSource * tmp_src_
Temporary pointer to the source dataset.
Definition: gicp.h:256
void applyState(Eigen::Matrix4f &t, const Vector6d &x) const
compute transformation matrix from transformation matrix
Definition: gicp.hpp:472
PointCloudSource::Ptr PointCloudSourcePtr
Definition: gicp.h:83
const std::vector< int > * tmp_idx_tgt_
Temporary pointer to the target dataset indices.
Definition: gicp.h:265
void setInputCloud(const PointCloudSourceConstPtr &cloud)
Provide a pointer to the input dataset.
Definition: gicp.hpp:48
boost::shared_ptr< const PointCloud< PointSource > > ConstPtr
Definition: point_cloud.h:429
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:296
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:238
double getRotationEpsilon()
Get the rotation epsilon (maximum allowable difference between two consecutive rotations) as set by t...
Definition: gicp.h:206
boost::shared_ptr< KdTree< PointT, Tree > > Ptr
Definition: kdtree.h:79
PointCloudTargetConstPtr target_
The input point cloud dataset target.
Definition: registration.h:502
const PointCloudTarget * tmp_tgt_
Temporary pointer to the target dataset.
Definition: gicp.h:259
pcl::PointCloud< PointTarget > PointCloudTarget
Definition: gicp.h:86
Registration< PointSource, PointTarget >::KdTreePtr InputKdTreePtr
Definition: gicp.h:94
double gicp_epsilon_
The epsilon constant for gicp paper; this is NOT the convergence tolerence default: 0...
Definition: gicp.h:244
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:221
Registration represents the base registration class for general purpose, ICP-like methods...
Definition: registration.h:62
std::vector< Eigen::Matrix3d > target_covariances_
Target cloud points covariances.
Definition: gicp.h:272
double rotation_epsilon_
The epsilon constant for rotation error.
Definition: gicp.h:250
boost::shared_ptr< ::pcl::PointIndices > Ptr
Definition: PointIndices.h:22
boost::shared_ptr< GeneralizedIterativeClosestPoint< PointSource, PointTarget > > Ptr
Definition: gicp.h:96
double transformation_epsilon_
The maximum difference between two consecutive transformations in order to consider convergence (user...
Definition: registration.h:516
void setInputSource(const PointCloudSourceConstPtr &cloud)
Provide a pointer to the input dataset.
Definition: gicp.h:133
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:178
OptimizationFunctorWithIndices(const GeneralizedIterativeClosestPoint *gicp)
Definition: gicp.h:334
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
PointCloudConstPtr input_
The input point cloud dataset.
Definition: pcl_base.h:150
PointCloudTarget::Ptr PointCloudTargetPtr
Definition: gicp.h:87
Eigen::Matrix< double, 6, 1 > Vector6d
Definition: gicp.h:100
std::vector< Eigen::Matrix3d > input_covariances_
Input cloud points covariances.
Definition: gicp.h:269
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:97
const Eigen::Matrix3d & mahalanobis(size_t index) const
Definition: gicp.h:178
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:215
GeneralizedIterativeClosestPoint is an ICP variant that implements the generalized iterative closest ...
Definition: gicp.h:60
boost::shared_ptr< ::pcl::PointIndices const > ConstPtr
Definition: PointIndices.h:23