Point Cloud Library (PCL) 1.14.0
Loading...
Searching...
No Matches
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/bfgs.h>
44#include <pcl/registration/icp.h>
45
46namespace pcl {
47/** \brief GeneralizedIterativeClosestPoint is an ICP variant that implements the
48 * generalized iterative closest point algorithm as described by Alex Segal et al. in
49 * http://www.robots.ox.ac.uk/~avsegal/resources/papers/Generalized_ICP.pdf
50 * The approach is based on using anisotropic cost functions to optimize the alignment
51 * after closest point assignments have been made.
52 * The original code uses GSL and ANN while in ours we use FLANN and Newton's method
53 * for optimization (call `useBFGS` to switch to BFGS optimizer, however Newton
54 * is usually faster and more accurate).
55 * \author Nizar Sallem
56 * \ingroup registration
57 */
58template <typename PointSource, typename PointTarget, typename Scalar = float>
60: public IterativeClosestPoint<PointSource, PointTarget, Scalar> {
61public:
62 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::reg_name_;
63 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::getClassName;
64 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::indices_;
65 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::target_;
66 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::input_;
67 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::tree_;
68 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::tree_reciprocal_;
69 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::nr_iterations_;
70 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::max_iterations_;
71 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::
73 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::final_transformation_;
74 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::transformation_;
75 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::
77 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::converged_;
78 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::corr_dist_threshold_;
79 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::inlier_threshold_;
80 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::
82 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::update_visualizer_;
83
87
91
94
96 std::vector<Eigen::Matrix3d, Eigen::aligned_allocator<Eigen::Matrix3d>>;
97 using MatricesVectorPtr = shared_ptr<MatricesVector>;
98 using MatricesVectorConstPtr = shared_ptr<const MatricesVector>;
99
103
104 using Ptr =
105 shared_ptr<GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>>;
106 using ConstPtr = shared_ptr<
108
109 using Vector3 = typename Eigen::Matrix<Scalar, 3, 1>;
110 using Vector4 = typename Eigen::Matrix<Scalar, 4, 1>;
111 using Vector6d = Eigen::Matrix<double, 6, 1>;
112 using Matrix3 = typename Eigen::Matrix<Scalar, 3, 3>;
113 using Matrix4 =
115 using Matrix6d = Eigen::Matrix<double, 6, 6>;
116 using AngleAxis = typename Eigen::AngleAxis<Scalar>;
117
119
120 /** \brief Empty constructor. */
122 {
124 reg_name_ = "GeneralizedIterativeClosestPoint";
125 max_iterations_ = 200;
128 rigid_transformation_estimation_ = [this](const PointCloudSource& cloud_src,
129 const pcl::Indices& indices_src,
130 const PointCloudTarget& cloud_tgt,
131 const pcl::Indices& indices_tgt,
132 Matrix4& transformation_matrix) {
134 cloud_src, indices_src, cloud_tgt, indices_tgt, transformation_matrix);
135 };
136 }
137
138 /** \brief Provide a pointer to the input dataset
139 * \param cloud the const boost shared pointer to a PointCloud message
140 */
141 inline void
143 {
144
145 if (cloud->points.empty()) {
146 PCL_ERROR(
147 "[pcl::%s::setInputSource] Invalid or empty point cloud dataset given!\n",
148 getClassName().c_str());
149 return;
150 }
151 PointCloudSource input = *cloud;
152 // Set all the point.data[3] values to 1 to aid the rigid transformation
153 for (std::size_t i = 0; i < input.size(); ++i)
154 input[i].data[3] = 1.0;
155
157 input_covariances_.reset();
158 }
159
160 /** \brief Provide a pointer to the covariances of the input source (if computed
161 * externally!). If not set, GeneralizedIterativeClosestPoint will compute the
162 * covariances itself. Make sure to set the covariances AFTER setting the input source
163 * point cloud (setting the input source point cloud will reset the covariances).
164 * \param[in] covariances the input source covariances
165 */
166 inline void
168 {
169 input_covariances_ = covariances;
170 }
171
172 /** \brief Provide a pointer to the input target (e.g., the point cloud that we want
173 * to align the input source to) \param[in] target the input point cloud target
174 */
175 inline void
182
183 /** \brief Provide a pointer to the covariances of the input target (if computed
184 * externally!). If not set, GeneralizedIterativeClosestPoint will compute the
185 * covariances itself. Make sure to set the covariances AFTER setting the input source
186 * point cloud (setting the input source point cloud will reset the covariances).
187 * \param[in] covariances the input target covariances
188 */
189 inline void
191 {
192 target_covariances_ = covariances;
193 }
194
195 /** \brief Estimate a rigid rotation transformation between a source and a target
196 * point cloud using an iterative non-linear BFGS approach.
197 * \param[in] cloud_src the source point cloud dataset
198 * \param[in] indices_src the vector of indices describing
199 * the points of interest in \a cloud_src
200 * \param[in] cloud_tgt the target point cloud dataset
201 * \param[in] indices_tgt the vector of indices describing
202 * the correspondences of the interest points from \a indices_src
203 * \param[in,out] transformation_matrix the resultant transformation matrix
204 */
205 void
207 const pcl::Indices& indices_src,
208 const PointCloudTarget& cloud_tgt,
209 const pcl::Indices& indices_tgt,
210 Matrix4& transformation_matrix);
211
212 /** \brief Estimate a rigid rotation transformation between a source and a target
213 * point cloud using an iterative non-linear Newton approach.
214 * \param[in] cloud_src the source point cloud dataset
215 * \param[in] indices_src the vector of indices describing
216 * the points of interest in \a cloud_src
217 * \param[in] cloud_tgt the target point cloud dataset
218 * \param[in] indices_tgt the vector of indices describing
219 * the correspondences of the interest points from \a indices_src
220 * \param[in,out] transformation_matrix the resultant transformation matrix
221 */
222 void
224 const pcl::Indices& indices_src,
225 const PointCloudTarget& cloud_tgt,
226 const pcl::Indices& indices_tgt,
227 Matrix4& transformation_matrix);
228
229 /** \brief \return Mahalanobis distance matrix for the given point index */
230 inline const Eigen::Matrix3d&
231 mahalanobis(std::size_t index) const
232 {
233 assert(index < mahalanobis_.size());
234 return mahalanobis_[index];
235 }
236
237 /** \brief Computes the derivative of the cost function w.r.t rotation angles.
238 * rotation matrix is obtainded from rotation angles x[3], x[4] and x[5]
239 * \return d/d_Phi, d/d_Theta, d/d_Psi respectively in g[3], g[4] and g[5]
240 * \param[in] x array representing 3D transformation
241 * \param[in] dCost_dR_T the transpose of the derivative of the cost function w.r.t
242 * rotation matrix
243 * \param[out] g gradient vector
244 */
245 void
247 const Eigen::Matrix3d& dCost_dR_T,
248 Vector6d& g) const;
249
250 /** \brief Set the rotation epsilon (maximum allowable difference between two
251 * consecutive rotations) in order for an optimization to be considered as having
252 * converged to the final solution.
253 * \param epsilon the rotation epsilon
254 */
255 inline void
256 setRotationEpsilon(double epsilon)
257 {
258 rotation_epsilon_ = epsilon;
259 }
260
261 /** \brief Get the rotation epsilon (maximum allowable difference between two
262 * consecutive rotations) as set by the user.
263 */
264 inline double
266 {
267 return rotation_epsilon_;
268 }
269
270 /** \brief Set the number of neighbors used when selecting a point neighbourhood
271 * to compute covariances.
272 * A higher value will bring more accurate covariance matrix but will make
273 * covariances computation slower.
274 * \param k the number of neighbors to use when computing covariances
275 */
276 void
281
282 /** \brief Get the number of neighbors used when computing covariances as set by
283 * the user
284 */
285 int
287 {
288 return k_correspondences_;
289 }
290
291 /** \brief Use BFGS optimizer instead of default Newton optimizer
292 */
293 void
295 {
296 rigid_transformation_estimation_ = [this](const PointCloudSource& cloud_src,
297 const pcl::Indices& indices_src,
298 const PointCloudTarget& cloud_tgt,
299 const pcl::Indices& indices_tgt,
300 Matrix4& transformation_matrix) {
302 cloud_src, indices_src, cloud_tgt, indices_tgt, transformation_matrix);
303 };
304 }
305
306 /** \brief Set maximum number of iterations at the optimization step
307 * \param[in] max maximum number of iterations for the optimizer
308 */
309 void
314
315 /** \brief Return maximum number of iterations at the optimization step
316 */
317 int
322
323 /** \brief Set the minimal translation gradient threshold for early optimization stop
324 * \param[in] tolerance translation gradient threshold in meters
325 */
326 void
328 {
330 }
331
332 /** \brief Return the minimal translation gradient threshold for early optimization
333 * stop
334 */
335 double
340
341 /** \brief Set the minimal rotation gradient threshold for early optimization stop
342 * \param[in] tolerance rotation gradient threshold in radians
343 */
344 void
346 {
348 }
349
350 /** \brief Return the minimal rotation gradient threshold for early optimization stop
351 */
352 double
357
358protected:
359 /** \brief The number of neighbors used for covariances computation.
360 * default: 20
361 */
363
364 /** \brief The epsilon constant for gicp paper; this is NOT the convergence
365 * tolerance
366 * default: 0.001
367 */
368 double gicp_epsilon_{0.001};
369
370 /** The epsilon constant for rotation error. (In GICP the transformation epsilon
371 * is split in rotation part and translation part).
372 * default: 2e-3
373 */
374 double rotation_epsilon_{2e-3};
375
376 /** \brief base transformation */
378
379 /** \brief Temporary pointer to the source dataset. */
381
382 /** \brief Temporary pointer to the target dataset. */
384
385 /** \brief Temporary pointer to the source dataset indices. */
387
388 /** \brief Temporary pointer to the target dataset indices. */
390
391 /** \brief Input cloud points covariances. */
393
394 /** \brief Target cloud points covariances. */
396
397 /** \brief Mahalanobis matrices holder. */
398 std::vector<Eigen::Matrix3d> mahalanobis_;
399
400 /** \brief maximum number of optimizations */
402
403 /** \brief minimal translation gradient for early optimization stop */
405
406 /** \brief minimal rotation gradient for early optimization stop */
408
409 /** \brief compute points covariances matrices according to the K nearest
410 * neighbors. K is set via setCorrespondenceRandomness() method.
411 * \param[in] cloud pointer to point cloud
412 * \param[in] tree KD tree performer for nearest neighbors search
413 * \param[out] cloud_covariances covariances matrices for each point in the cloud
414 */
415 template <typename PointT>
416 void
418 const typename pcl::search::KdTree<PointT>::Ptr tree,
419 MatricesVector& cloud_covariances);
420
421 /** \return trace of mat1 . mat2
422 * \param mat1 matrix of dimension nxm
423 * \param mat2 matrix of dimension mxp
424 */
425 inline double
426 matricesInnerProd(const Eigen::MatrixXd& mat1, const Eigen::MatrixXd& mat2) const
427 {
428 if (mat1.cols() != mat2.rows()) {
429 PCL_THROW_EXCEPTION(PCLException,
430 "The two matrices' shapes don't match. "
431 "They are ("
432 << mat1.rows() << ", " << mat1.cols() << ") and ("
433 << mat2.rows() << ", " << mat2.cols() << ")");
434 }
435 return (mat1 * mat2).trace();
436 }
437
438 /** \brief Rigid transformation computation method with initial guess.
439 * \param output the transformed input point cloud dataset using the rigid
440 * transformation found \param guess the initial guess of the transformation to
441 * compute
442 */
443 void
444 computeTransformation(PointCloudSource& output, const Matrix4& guess) override;
445
446 /** \brief Search for the closest nearest neighbor of a given point.
447 * \param query the point to search a nearest neighbour for
448 * \param index vector of size 1 to store the index of the nearest neighbour found
449 * \param distance vector of size 1 to store the distance to nearest neighbour found
450 */
451 inline bool
452 searchForNeighbors(const PointSource& query,
453 pcl::Indices& index,
454 std::vector<float>& distance)
455 {
456 int k = tree_->nearestKSearch(query, 1, index, distance);
457 if (k == 0)
458 return (false);
459 return (true);
460 }
461
462 /// \brief compute transformation matrix from transformation matrix
463 void
464 applyState(Matrix4& t, const Vector6d& x) const;
465
466 /// \brief optimization functor structure
471 double
472 operator()(const Vector6d& x) override;
473 void
474 df(const Vector6d& x, Vector6d& df) override;
475 void
476 fdf(const Vector6d& x, double& f, Vector6d& df) override;
477 void
478 dfddf(const Vector6d& x, Vector6d& df, Matrix6d& ddf);
480 checkGradient(const Vector6d& g) override;
481
483 };
484
485 std::function<void(const pcl::PointCloud<PointSource>& cloud_src,
486 const pcl::Indices& src_indices,
487 const pcl::PointCloud<PointTarget>& cloud_tgt,
488 const pcl::Indices& tgt_indices,
489 Matrix4& transformation_matrix)>
491
492private:
493 void
494 getRDerivatives(double phi,
495 double theta,
496 double psi,
497 Eigen::Matrix3d& dR_dPhi,
498 Eigen::Matrix3d& dR_dTheta,
499 Eigen::Matrix3d& dR_dPsi) const;
500
501 void
502 getR2ndDerivatives(double phi,
503 double theta,
504 double psi,
505 Eigen::Matrix3d& ddR_dPhi_dPhi,
506 Eigen::Matrix3d& ddR_dPhi_dTheta,
507 Eigen::Matrix3d& ddR_dPhi_dPsi,
508 Eigen::Matrix3d& ddR_dTheta_dTheta,
509 Eigen::Matrix3d& ddR_dTheta_dPsi,
510 Eigen::Matrix3d& ddR_dPsi_dPsi) const;
511};
512} // namespace pcl
513
514#include <pcl/registration/impl/gicp.hpp>
GeneralizedIterativeClosestPoint is an ICP variant that implements the generalized iterative closest ...
Definition gicp.h:60
double rotation_epsilon_
The epsilon constant for rotation error.
Definition gicp.h:374
void estimateRigidTransformationBFGS(const PointCloudSource &cloud_src, const pcl::Indices &indices_src, const PointCloudTarget &cloud_tgt, const pcl::Indices &indices_tgt, Matrix4 &transformation_matrix)
Estimate a rigid rotation transformation between a source and a target point cloud using an iterative...
Definition gicp.hpp:274
void setTranslationGradientTolerance(double tolerance)
Set the minimal translation gradient threshold for early optimization stop.
Definition gicp.h:327
int getCorrespondenceRandomness() const
Get the number of neighbors used when computing covariances as set by the user.
Definition gicp.h:286
void setCorrespondenceRandomness(int k)
Set the number of neighbors used when selecting a point neighbourhood to compute covariances.
Definition gicp.h:277
typename Registration< PointSource, PointTarget, Scalar >::KdTree InputKdTree
Definition gicp.h:100
typename IterativeClosestPoint< PointSource, PointTarget, Scalar >::Matrix4 Matrix4
Definition gicp.h:114
void applyState(Matrix4 &t, const Vector6d &x) const
compute transformation matrix from transformation matrix
Definition gicp.hpp:903
pcl::PointCloud< PointTarget > PointCloudTarget
Definition gicp.h:88
const pcl::Indices * tmp_idx_tgt_
Temporary pointer to the target dataset indices.
Definition gicp.h:389
pcl::PointCloud< PointSource > PointCloudSource
Definition gicp.h:84
Matrix4 base_transformation_
base transformation
Definition gicp.h:377
PointIndices::ConstPtr PointIndicesConstPtr
Definition gicp.h:93
shared_ptr< GeneralizedIterativeClosestPoint< PointSource, PointTarget, Scalar > > Ptr
Definition gicp.h:105
double translation_gradient_tolerance_
minimal translation gradient for early optimization stop
Definition gicp.h:404
Eigen::Matrix< double, 6, 6 > Matrix6d
Definition gicp.h:115
const PointCloudTarget * tmp_tgt_
Temporary pointer to the target dataset.
Definition gicp.h:383
const Eigen::Matrix3d & mahalanobis(std::size_t index) const
Definition gicp.h:231
int getMaximumOptimizerIterations() const
Return maximum number of iterations at the optimization step.
Definition gicp.h:318
MatricesVectorPtr input_covariances_
Input cloud points covariances.
Definition gicp.h:392
typename PointCloudSource::ConstPtr PointCloudSourceConstPtr
Definition gicp.h:86
typename Eigen::Matrix< Scalar, 4, 1 > Vector4
Definition gicp.h:110
typename Eigen::Matrix< Scalar, 3, 1 > Vector3
Definition gicp.h:109
void setInputSource(const PointCloudSourceConstPtr &cloud) override
Provide a pointer to the input dataset.
Definition gicp.h:142
void setTargetCovariances(const MatricesVectorPtr &covariances)
Provide a pointer to the covariances of the input target (if computed externally!).
Definition gicp.h:190
std::vector< Eigen::Matrix3d, Eigen::aligned_allocator< Eigen::Matrix3d > > MatricesVector
Definition gicp.h:96
void setSourceCovariances(const MatricesVectorPtr &covariances)
Provide a pointer to the covariances of the input source (if computed externally!).
Definition gicp.h:167
shared_ptr< const MatricesVector > MatricesVectorConstPtr
Definition gicp.h:98
typename Registration< PointSource, PointTarget, Scalar >::KdTreePtr InputKdTreePtr
Definition gicp.h:102
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:51
void estimateRigidTransformationNewton(const PointCloudSource &cloud_src, const pcl::Indices &indices_src, const PointCloudTarget &cloud_tgt, const pcl::Indices &indices_tgt, Matrix4 &transformation_matrix)
Estimate a rigid rotation transformation between a source and a target point cloud using an iterative...
Definition gicp.hpp:350
void useBFGS()
Use BFGS optimizer instead of default Newton optimizer.
Definition gicp.h:294
typename PointCloudSource::Ptr PointCloudSourcePtr
Definition gicp.h:85
typename PointCloudTarget::Ptr PointCloudTargetPtr
Definition gicp.h:89
const PointCloudSource * tmp_src_
Temporary pointer to the source dataset.
Definition gicp.h:380
int max_inner_iterations_
maximum number of optimizations
Definition gicp.h:401
double gicp_epsilon_
The epsilon constant for gicp paper; this is NOT the convergence tolerance default: 0....
Definition gicp.h:368
double getRotationEpsilon() const
Get the rotation epsilon (maximum allowable difference between two consecutive rotations) as set by t...
Definition gicp.h:265
shared_ptr< const GeneralizedIterativeClosestPoint< PointSource, PointTarget, Scalar > > ConstPtr
Definition gicp.h:107
void setRotationEpsilon(double epsilon)
Set the rotation epsilon (maximum allowable difference between two consecutive rotations) in order fo...
Definition gicp.h:256
double matricesInnerProd(const Eigen::MatrixXd &mat1, const Eigen::MatrixXd &mat2) const
Definition gicp.h:426
PCL_MAKE_ALIGNED_OPERATOR_NEW GeneralizedIterativeClosestPoint()
Empty constructor.
Definition gicp.h:121
PointIndices::Ptr PointIndicesPtr
Definition gicp.h:92
double getRotationGradientTolerance() const
Return the minimal rotation gradient threshold for early optimization stop.
Definition gicp.h:353
int k_correspondences_
The number of neighbors used for covariances computation.
Definition gicp.h:362
std::vector< Eigen::Matrix3d > mahalanobis_
Mahalanobis matrices holder.
Definition gicp.h:398
void setMaximumOptimizerIterations(int max)
Set maximum number of iterations at the optimization step.
Definition gicp.h:310
typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr
Definition gicp.h:90
MatricesVectorPtr target_covariances_
Target cloud points covariances.
Definition gicp.h:395
void computeRDerivative(const Vector6d &x, const Eigen::Matrix3d &dCost_dR_T, Vector6d &g) const
Computes the derivative of the cost function w.r.t rotation angles.
Definition gicp.hpp:182
typename Eigen::AngleAxis< Scalar > AngleAxis
Definition gicp.h:116
void computeTransformation(PointCloudSource &output, const Matrix4 &guess) override
Rigid transformation computation method with initial guess.
Definition gicp.hpp:747
double getTranslationGradientTolerance() const
Return the minimal translation gradient threshold for early optimization stop.
Definition gicp.h:336
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:176
typename Eigen::Matrix< Scalar, 3, 3 > Matrix3
Definition gicp.h:112
shared_ptr< MatricesVector > MatricesVectorPtr
Definition gicp.h:97
double rotation_gradient_tolerance_
minimal rotation gradient for early optimization stop
Definition gicp.h:407
std::function< void(const pcl::PointCloud< PointSource > &cloud_src, const pcl::Indices &src_indices, const pcl::PointCloud< PointTarget > &cloud_tgt, const pcl::Indices &tgt_indices, Matrix4 &transformation_matrix)> rigid_transformation_estimation_
Definition gicp.h:490
void setRotationGradientTolerance(double tolerance)
Set the minimal rotation gradient threshold for early optimization stop.
Definition gicp.h:345
bool searchForNeighbors(const PointSource &query, pcl::Indices &index, std::vector< float > &distance)
Search for the closest nearest neighbor of a given point.
Definition gicp.h:452
Eigen::Matrix< double, 6, 1 > Vector6d
Definition gicp.h:111
const pcl::Indices * tmp_idx_src_
Temporary pointer to the source dataset indices.
Definition gicp.h:386
IterativeClosestPoint provides a base implementation of the Iterative Closest Point algorithm.
Definition icp.h:98
typename Registration< PointSource, PointTarget, Scalar >::Matrix4 Matrix4
Definition icp.h:143
void setInputTarget(const PointCloudTargetConstPtr &cloud) override
Provide a pointer to the input target (e.g., the point cloud that we want to align the input source t...
Definition icp.h:232
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:199
PointCloudConstPtr input_
The input point cloud dataset.
Definition pcl_base.h:147
IndicesPtr indices_
A pointer to the vector of point indices to use.
Definition pcl_base.h:150
A base class for all pcl exceptions which inherits from std::runtime_error.
Definition exceptions.h:64
std::size_t size() const
shared_ptr< PointCloud< PointSource > > Ptr
shared_ptr< const PointCloud< PointSource > > ConstPtr
Matrix4 final_transformation_
The final transformation matrix estimated by the registration method after N iterations.
std::function< UpdateVisualizerCallbackSignature > update_visualizer_
Callback function to update intermediate source point cloud position during it's registration to the ...
double corr_dist_threshold_
The maximum distance threshold between two correspondent points in source <-> target.
std::string reg_name_
The registration method name.
Matrix4 transformation_
The transformation matrix estimated by the registration method.
KdTreeReciprocalPtr tree_reciprocal_
A pointer to the spatial search object of the source.
typename KdTree::Ptr KdTreePtr
int nr_iterations_
The number of iterations the internal optimization ran for (used internally).
KdTreePtr tree_
A pointer to the spatial search object.
Matrix4 previous_transformation_
The previous transformation matrix estimated by the registration method (used internally).
bool converged_
Holds internal convergence state, given user parameters.
int max_iterations_
The maximum number of iterations the internal optimization should run for.
unsigned int min_number_correspondences_
The minimum number of correspondences that the algorithm needs before attempting to estimate the tran...
double inlier_threshold_
The inlier distance threshold for the internal RANSAC outlier rejection loop.
double transformation_epsilon_
The maximum difference between two consecutive transformations in order to consider convergence (user...
PointCloudTargetConstPtr target_
The input point cloud dataset target.
const std::string & getClassName() const
Abstract class get name method.
search::KdTree is a wrapper class which inherits the pcl::KdTree class for performing search function...
Definition kdtree.h:62
shared_ptr< KdTree< PointT, Tree > > Ptr
Definition kdtree.h:75
#define PCL_MAKE_ALIGNED_OPERATOR_NEW
Macro to signal a class requires a custom allocator.
Definition memory.h:63
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition types.h:133
void dfddf(const Vector6d &x, Vector6d &df, Matrix6d &ddf)
Definition gicp.hpp:578
OptimizationFunctorWithIndices(const GeneralizedIterativeClosestPoint *gicp)
Definition gicp.h:468
void df(const Vector6d &x, Vector6d &df) override
Definition gicp.hpp:491
BFGSSpace::Status checkGradient(const Vector6d &g) override
Definition gicp.hpp:724
void fdf(const Vector6d &x, double &f, Vector6d &df) override
Definition gicp.hpp:534
shared_ptr< ::pcl::PointIndices > Ptr
shared_ptr< const ::pcl::PointIndices > ConstPtr