Point Cloud Library (PCL) 1.13.1
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 an eigen mapped BFGS and
53 * FLANN.
54 * \author Nizar Sallem
55 * \ingroup registration
56 */
57template <typename PointSource, typename PointTarget, typename Scalar = float>
59: public IterativeClosestPoint<PointSource, PointTarget, Scalar> {
60public:
61 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::reg_name_;
62 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::getClassName;
63 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::indices_;
64 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::target_;
65 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::input_;
66 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::tree_;
67 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::tree_reciprocal_;
68 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::nr_iterations_;
69 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::max_iterations_;
70 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::
72 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::final_transformation_;
73 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::transformation_;
74 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::
76 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::converged_;
77 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::corr_dist_threshold_;
78 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::inlier_threshold_;
79 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::
81 using IterativeClosestPoint<PointSource, PointTarget, Scalar>::update_visualizer_;
82
86
90
93
95 std::vector<Eigen::Matrix3d, Eigen::aligned_allocator<Eigen::Matrix3d>>;
96 using MatricesVectorPtr = shared_ptr<MatricesVector>;
97 using MatricesVectorConstPtr = shared_ptr<const MatricesVector>;
98
102
103 using Ptr =
104 shared_ptr<GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>>;
105 using ConstPtr = shared_ptr<
107
108 using Vector3 = typename Eigen::Matrix<Scalar, 3, 1>;
109 using Vector4 = typename Eigen::Matrix<Scalar, 4, 1>;
110 using Vector6d = Eigen::Matrix<double, 6, 1>;
111 using Matrix3 = typename Eigen::Matrix<Scalar, 3, 3>;
112 using Matrix4 =
114 using AngleAxis = typename Eigen::AngleAxis<Scalar>;
115
117
118 /** \brief Empty constructor. */
121 , gicp_epsilon_(0.001)
122 , rotation_epsilon_(2e-3)
123 , mahalanobis_(0)
127 {
129 reg_name_ = "GeneralizedIterativeClosestPoint";
130 max_iterations_ = 200;
133 rigid_transformation_estimation_ = [this](const PointCloudSource& cloud_src,
134 const pcl::Indices& indices_src,
135 const PointCloudTarget& cloud_tgt,
136 const pcl::Indices& indices_tgt,
137 Matrix4& transformation_matrix) {
139 cloud_src, indices_src, cloud_tgt, indices_tgt, transformation_matrix);
140 };
141 }
142
143 /** \brief Provide a pointer to the input dataset
144 * \param cloud the const boost shared pointer to a PointCloud message
145 */
146 inline void
148 {
149
150 if (cloud->points.empty()) {
151 PCL_ERROR(
152 "[pcl::%s::setInputSource] Invalid or empty point cloud dataset given!\n",
153 getClassName().c_str());
154 return;
155 }
156 PointCloudSource input = *cloud;
157 // Set all the point.data[3] values to 1 to aid the rigid transformation
158 for (std::size_t i = 0; i < input.size(); ++i)
159 input[i].data[3] = 1.0;
160
162 input_covariances_.reset();
163 }
164
165 /** \brief Provide a pointer to the covariances of the input source (if computed
166 * externally!). If not set, GeneralizedIterativeClosestPoint will compute the
167 * covariances itself. Make sure to set the covariances AFTER setting the input source
168 * point cloud (setting the input source point cloud will reset the covariances).
169 * \param[in] covariances the input source covariances
170 */
171 inline void
173 {
174 input_covariances_ = covariances;
175 }
176
177 /** \brief Provide a pointer to the input target (e.g., the point cloud that we want
178 * to align the input source to) \param[in] target the input point cloud target
179 */
180 inline void
187
188 /** \brief Provide a pointer to the covariances of the input target (if computed
189 * externally!). If not set, GeneralizedIterativeClosestPoint will compute the
190 * covariances itself. Make sure to set the covariances AFTER setting the input source
191 * point cloud (setting the input source point cloud will reset the covariances).
192 * \param[in] covariances the input target covariances
193 */
194 inline void
196 {
197 target_covariances_ = covariances;
198 }
199
200 /** \brief Estimate a rigid rotation transformation between a source and a target
201 * point cloud using an iterative non-linear BFGS approach.
202 * \param[in] cloud_src the source point cloud dataset
203 * \param[in] indices_src the vector of indices describing
204 * the points of interest in \a cloud_src
205 * \param[in] cloud_tgt the target point cloud dataset
206 * \param[in] indices_tgt the vector of indices describing
207 * the correspondences of the interest points from \a indices_src
208 * \param[in,out] transformation_matrix the resultant transformation matrix
209 */
210 void
212 const pcl::Indices& indices_src,
213 const PointCloudTarget& cloud_tgt,
214 const pcl::Indices& indices_tgt,
215 Matrix4& transformation_matrix);
216
217 /** \brief \return Mahalanobis distance matrix for the given point index */
218 inline const Eigen::Matrix3d&
219 mahalanobis(std::size_t index) const
220 {
221 assert(index < mahalanobis_.size());
222 return mahalanobis_[index];
223 }
224
225 /** \brief Computes the derivative of the cost function w.r.t rotation angles.
226 * rotation matrix is obtainded from rotation angles x[3], x[4] and x[5]
227 * \return d/d_Phi, d/d_Theta, d/d_Psi respectively in g[3], g[4] and g[5]
228 * \param[in] x array representing 3D transformation
229 * \param[in] dCost_dR_T the transpose of the derivative of the cost function w.r.t
230 * rotation matrix
231 * \param[out] g gradient vector
232 */
233 void
235 const Eigen::Matrix3d& dCost_dR_T,
236 Vector6d& g) const;
237
238 /** \brief Set the rotation epsilon (maximum allowable difference between two
239 * consecutive rotations) in order for an optimization to be considered as having
240 * converged to the final solution.
241 * \param epsilon the rotation epsilon
242 */
243 inline void
244 setRotationEpsilon(double epsilon)
245 {
246 rotation_epsilon_ = epsilon;
247 }
248
249 /** \brief Get the rotation epsilon (maximum allowable difference between two
250 * consecutive rotations) as set by the user.
251 */
252 inline double
254 {
255 return rotation_epsilon_;
256 }
257
258 /** \brief Set the number of neighbors used when selecting a point neighbourhood
259 * to compute covariances.
260 * A higher value will bring more accurate covariance matrix but will make
261 * covariances computation slower.
262 * \param k the number of neighbors to use when computing covariances
263 */
264 void
269
270 /** \brief Get the number of neighbors used when computing covariances as set by
271 * the user
272 */
273 int
275 {
276 return k_correspondences_;
277 }
278
279 /** \brief Set maximum number of iterations at the optimization step
280 * \param[in] max maximum number of iterations for the optimizer
281 */
282 void
287
288 /** \brief Return maximum number of iterations at the optimization step
289 */
290 int
295
296 /** \brief Set the minimal translation gradient threshold for early optimization stop
297 * \param[in] tolerance translation gradient threshold in meters
298 */
299 void
301 {
303 }
304
305 /** \brief Return the minimal translation gradient threshold for early optimization
306 * stop
307 */
308 double
313
314 /** \brief Set the minimal rotation gradient threshold for early optimization stop
315 * \param[in] tolerance rotation gradient threshold in radians
316 */
317 void
319 {
321 }
322
323 /** \brief Return the minimal rotation gradient threshold for early optimization stop
324 */
325 double
330
331protected:
332 /** \brief The number of neighbors used for covariances computation.
333 * default: 20
334 */
336
337 /** \brief The epsilon constant for gicp paper; this is NOT the convergence
338 * tolerance
339 * default: 0.001
340 */
342
343 /** The epsilon constant for rotation error. (In GICP the transformation epsilon
344 * is split in rotation part and translation part).
345 * default: 2e-3
346 */
348
349 /** \brief base transformation */
351
352 /** \brief Temporary pointer to the source dataset. */
354
355 /** \brief Temporary pointer to the target dataset. */
357
358 /** \brief Temporary pointer to the source dataset indices. */
360
361 /** \brief Temporary pointer to the target dataset indices. */
363
364 /** \brief Input cloud points covariances. */
366
367 /** \brief Target cloud points covariances. */
369
370 /** \brief Mahalanobis matrices holder. */
371 std::vector<Eigen::Matrix3d> mahalanobis_;
372
373 /** \brief maximum number of optimizations */
375
376 /** \brief minimal translation gradient for early optimization stop */
378
379 /** \brief minimal rotation gradient for early optimization stop */
381
382 /** \brief compute points covariances matrices according to the K nearest
383 * neighbors. K is set via setCorrespondenceRandomness() method.
384 * \param cloud pointer to point cloud
385 * \param tree KD tree performer for nearest neighbors search
386 * \param[out] cloud_covariances covariances matrices for each point in the cloud
387 */
388 template <typename PointT>
389 void
391 const typename pcl::search::KdTree<PointT>::Ptr tree,
392 MatricesVector& cloud_covariances);
393
394 /** \return trace of mat1 . mat2
395 * \param mat1 matrix of dimension nxm
396 * \param mat2 matrix of dimension mxp
397 */
398 inline double
399 matricesInnerProd(const Eigen::MatrixXd& mat1, const Eigen::MatrixXd& mat2) const
400 {
401 if (mat1.cols() != mat2.rows()) {
402 PCL_THROW_EXCEPTION(PCLException,
403 "The two matrices' shapes don't match. "
404 "They are ("
405 << mat1.rows() << ", " << mat1.cols() << ") and ("
406 << mat2.rows() << ", " << mat2.cols() << ")");
407 }
408 return (mat1 * mat2).trace();
409 }
410
411 /** \brief Rigid transformation computation method with initial guess.
412 * \param output the transformed input point cloud dataset using the rigid
413 * transformation found \param guess the initial guess of the transformation to
414 * compute
415 */
416 void
417 computeTransformation(PointCloudSource& output, const Matrix4& guess) override;
418
419 /** \brief Search for the closest nearest neighbor of a given point.
420 * \param query the point to search a nearest neighbour for
421 * \param index vector of size 1 to store the index of the nearest neighbour found
422 * \param distance vector of size 1 to store the distance to nearest neighbour found
423 */
424 inline bool
425 searchForNeighbors(const PointSource& query,
426 pcl::Indices& index,
427 std::vector<float>& distance)
428 {
429 int k = tree_->nearestKSearch(query, 1, index, distance);
430 if (k == 0)
431 return (false);
432 return (true);
433 }
434
435 /// \brief compute transformation matrix from transformation matrix
436 void
437 applyState(Matrix4& t, const Vector6d& x) const;
438
439 /// \brief optimization functor structure
444 double
445 operator()(const Vector6d& x) override;
446 void
447 df(const Vector6d& x, Vector6d& df) override;
448 void
449 fdf(const Vector6d& x, double& f, Vector6d& df) override;
451 checkGradient(const Vector6d& g) override;
452
454 };
455
456 std::function<void(const pcl::PointCloud<PointSource>& cloud_src,
457 const pcl::Indices& src_indices,
458 const pcl::PointCloud<PointTarget>& cloud_tgt,
459 const pcl::Indices& tgt_indices,
460 Matrix4& transformation_matrix)>
462};
463} // namespace pcl
464
465#include <pcl/registration/impl/gicp.hpp>
GeneralizedIterativeClosestPoint is an ICP variant that implements the generalized iterative closest ...
Definition gicp.h:59
double rotation_epsilon_
The epsilon constant for rotation error.
Definition gicp.h:347
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:189
void setTranslationGradientTolerance(double tolerance)
Set the minimal translation gradient threshold for early optimization stop.
Definition gicp.h:300
int getCorrespondenceRandomness() const
Get the number of neighbors used when computing covariances as set by the user.
Definition gicp.h:274
void setCorrespondenceRandomness(int k)
Set the number of neighbors used when selecting a point neighbourhood to compute covariances.
Definition gicp.h:265
typename Registration< PointSource, PointTarget, Scalar >::KdTree InputKdTree
Definition gicp.h:99
typename IterativeClosestPoint< PointSource, PointTarget, Scalar >::Matrix4 Matrix4
Definition gicp.h:113
void applyState(Matrix4 &t, const Vector6d &x) const
compute transformation matrix from transformation matrix
Definition gicp.hpp:562
pcl::PointCloud< PointTarget > PointCloudTarget
Definition gicp.h:87
const pcl::Indices * tmp_idx_tgt_
Temporary pointer to the target dataset indices.
Definition gicp.h:362
pcl::PointCloud< PointSource > PointCloudSource
Definition gicp.h:83
Matrix4 base_transformation_
base transformation
Definition gicp.h:350
PointIndices::ConstPtr PointIndicesConstPtr
Definition gicp.h:92
shared_ptr< GeneralizedIterativeClosestPoint< PointSource, PointTarget, Scalar > > Ptr
Definition gicp.h:104
double translation_gradient_tolerance_
minimal translation gradient for early optimization stop
Definition gicp.h:377
const PointCloudTarget * tmp_tgt_
Temporary pointer to the target dataset.
Definition gicp.h:356
const Eigen::Matrix3d & mahalanobis(std::size_t index) const
Definition gicp.h:219
int getMaximumOptimizerIterations() const
Return maximum number of iterations at the optimization step.
Definition gicp.h:291
MatricesVectorPtr input_covariances_
Input cloud points covariances.
Definition gicp.h:365
typename PointCloudSource::ConstPtr PointCloudSourceConstPtr
Definition gicp.h:85
typename Eigen::Matrix< Scalar, 4, 1 > Vector4
Definition gicp.h:109
typename Eigen::Matrix< Scalar, 3, 1 > Vector3
Definition gicp.h:108
void setInputSource(const PointCloudSourceConstPtr &cloud) override
Provide a pointer to the input dataset.
Definition gicp.h:147
void setTargetCovariances(const MatricesVectorPtr &covariances)
Provide a pointer to the covariances of the input target (if computed externally!).
Definition gicp.h:195
std::vector< Eigen::Matrix3d, Eigen::aligned_allocator< Eigen::Matrix3d > > MatricesVector
Definition gicp.h:95
void setSourceCovariances(const MatricesVectorPtr &covariances)
Provide a pointer to the covariances of the input source (if computed externally!).
Definition gicp.h:172
shared_ptr< const MatricesVector > MatricesVectorConstPtr
Definition gicp.h:97
typename Registration< PointSource, PointTarget, Scalar >::KdTreePtr InputKdTreePtr
Definition gicp.h:101
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
typename PointCloudSource::Ptr PointCloudSourcePtr
Definition gicp.h:84
typename PointCloudTarget::Ptr PointCloudTargetPtr
Definition gicp.h:88
const PointCloudSource * tmp_src_
Temporary pointer to the source dataset.
Definition gicp.h:353
int max_inner_iterations_
maximum number of optimizations
Definition gicp.h:374
double gicp_epsilon_
The epsilon constant for gicp paper; this is NOT the convergence tolerance default: 0....
Definition gicp.h:341
double getRotationEpsilon() const
Get the rotation epsilon (maximum allowable difference between two consecutive rotations) as set by t...
Definition gicp.h:253
shared_ptr< const GeneralizedIterativeClosestPoint< PointSource, PointTarget, Scalar > > ConstPtr
Definition gicp.h:106
void setRotationEpsilon(double epsilon)
Set the rotation epsilon (maximum allowable difference between two consecutive rotations) in order fo...
Definition gicp.h:244
double matricesInnerProd(const Eigen::MatrixXd &mat1, const Eigen::MatrixXd &mat2) const
Definition gicp.h:399
PCL_MAKE_ALIGNED_OPERATOR_NEW GeneralizedIterativeClosestPoint()
Empty constructor.
Definition gicp.h:119
PointIndices::Ptr PointIndicesPtr
Definition gicp.h:91
double getRotationGradientTolerance() const
Return the minimal rotation gradient threshold for early optimization stop.
Definition gicp.h:326
int k_correspondences_
The number of neighbors used for covariances computation.
Definition gicp.h:335
std::vector< Eigen::Matrix3d > mahalanobis_
Mahalanobis matrices holder.
Definition gicp.h:371
void setMaximumOptimizerIterations(int max)
Set maximum number of iterations at the optimization step.
Definition gicp.h:283
typename PointCloudTarget::ConstPtr PointCloudTargetConstPtr
Definition gicp.h:89
MatricesVectorPtr target_covariances_
Target cloud points covariances.
Definition gicp.h:368
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:132
typename Eigen::AngleAxis< Scalar > AngleAxis
Definition gicp.h:114
void computeTransformation(PointCloudSource &output, const Matrix4 &guess) override
Rigid transformation computation method with initial guess.
Definition gicp.hpp:406
double getTranslationGradientTolerance() const
Return the minimal translation gradient threshold for early optimization stop.
Definition gicp.h:309
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:181
typename Eigen::Matrix< Scalar, 3, 3 > Matrix3
Definition gicp.h:111
shared_ptr< MatricesVector > MatricesVectorPtr
Definition gicp.h:96
double rotation_gradient_tolerance_
minimal rotation gradient for early optimization stop
Definition gicp.h:380
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:461
void setRotationGradientTolerance(double tolerance)
Set the minimal rotation gradient threshold for early optimization stop.
Definition gicp.h:318
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:425
Eigen::Matrix< double, 6, 1 > Vector6d
Definition gicp.h:110
const pcl::Indices * tmp_idx_src_
Temporary pointer to the source dataset indices.
Definition gicp.h:359
IterativeClosestPoint provides a base implementation of the Iterative Closest Point algorithm.
Definition icp.h:97
typename Registration< PointSource, PointTarget, Scalar >::Matrix4 Matrix4
Definition icp.h:142
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:240
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:207
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
OptimizationFunctorWithIndices(const GeneralizedIterativeClosestPoint *gicp)
Definition gicp.h:441
void df(const Vector6d &x, Vector6d &df) override
Definition gicp.hpp:296
BFGSSpace::Status checkGradient(const Vector6d &g) override
Definition gicp.hpp:383
void fdf(const Vector6d &x, double &f, Vector6d &df) override
Definition gicp.hpp:339
shared_ptr< ::pcl::PointIndices > Ptr
shared_ptr< const ::pcl::PointIndices > ConstPtr