Point Cloud Library (PCL)  1.14.0-dev
ia_fpcs.h
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2014-, Open Perception, Inc.
6  * Copyright (C) 2008 Ben Gurion University of the Negev, Beer Sheva, Israel.
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 are met
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the copyright holder(s) nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  */
37 
38 #pragma once
39 
40 #include <pcl/common/common.h>
41 #include <pcl/registration/matching_candidate.h>
42 #include <pcl/registration/registration.h>
43 
44 namespace pcl {
45 /** \brief Compute the mean point density of a given point cloud.
46  * \param[in] cloud pointer to the input point cloud
47  * \param[in] max_dist maximum distance of a point to be considered as a neighbor
48  * \param[in] nr_threads number of threads to use (default = 1, only used if OpenMP flag
49  * is set) \return the mean point density of a given point cloud
50  */
51 template <typename PointT>
52 inline float
54  float max_dist,
55  int nr_threads = 1);
56 
57 /** \brief Compute the mean point density of a given point cloud.
58  * \param[in] cloud pointer to the input point cloud
59  * \param[in] indices the vector of point indices to use from \a cloud
60  * \param[in] max_dist maximum distance of a point to be considered as a neighbor
61  * \param[in] nr_threads number of threads to use (default = 1, only used if OpenMP flag
62  * is set) \return the mean point density of a given point cloud
63  */
64 template <typename PointT>
65 inline float
67  const pcl::Indices& indices,
68  float max_dist,
69  int nr_threads = 1);
70 
71 namespace registration {
72 /** \brief FPCSInitialAlignment computes corresponding four point congruent sets as
73  * described in: "4-points congruent sets for robust pairwise surface registration",
74  * Dror Aiger, Niloy Mitra, Daniel Cohen-Or. ACM Transactions on Graphics, vol. 27(3),
75  * 2008 \author P.W.Theiler \ingroup registration
76  */
77 template <typename PointSource,
78  typename PointTarget,
79  typename NormalT = pcl::Normal,
80  typename Scalar = float>
81 class FPCSInitialAlignment : public Registration<PointSource, PointTarget, Scalar> {
82 public:
83  /** \cond */
84  using Ptr =
85  shared_ptr<FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scalar>>;
86  using ConstPtr =
87  shared_ptr<const FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scalar>>;
88 
91 
95  using PointCloudSourceIterator = typename PointCloudSource::iterator;
96 
97  using Normals = pcl::PointCloud<NormalT>;
98  using NormalsConstPtr = typename Normals::ConstPtr;
99 
102  /** \endcond */
103 
104  /** \brief Constructor.
105  * Resets the maximum number of iterations to 0 thus forcing an internal computation
106  * if not set by the user. Sets the number of RANSAC iterations to 1000 and the
107  * standard transformation estimation to TransformationEstimation3Point.
108  */
110 
111  /** \brief Destructor. */
112  ~FPCSInitialAlignment() override = default;
113 
114  /** \brief Provide a pointer to the vector of target indices.
115  * \param[in] target_indices a pointer to the target indices
116  */
117  inline void
118  setTargetIndices(const IndicesPtr& target_indices)
119  {
120  target_indices_ = target_indices;
121  };
122 
123  /** \return a pointer to the vector of target indices. */
124  inline IndicesPtr
126  {
127  return (target_indices_);
128  };
129 
130  /** \brief Provide a pointer to the normals of the source point cloud.
131  * \param[in] source_normals pointer to the normals of the source pointer cloud.
132  */
133  inline void
134  setSourceNormals(const NormalsConstPtr& source_normals)
135  {
136  source_normals_ = source_normals;
137  };
138 
139  /** \return the normals of the source point cloud. */
140  inline NormalsConstPtr
142  {
143  return (source_normals_);
144  };
145 
146  /** \brief Provide a pointer to the normals of the target point cloud.
147  * \param[in] target_normals point to the normals of the target point cloud.
148  */
149  inline void
150  setTargetNormals(const NormalsConstPtr& target_normals)
151  {
152  target_normals_ = target_normals;
153  };
154 
155  /** \return the normals of the target point cloud. */
156  inline NormalsConstPtr
158  {
159  return (target_normals_);
160  };
161 
162  /** \brief Set the number of used threads if OpenMP is activated.
163  * \param[in] nr_threads the number of used threads
164  */
165  inline void
166  setNumberOfThreads(int nr_threads)
167  {
168  nr_threads_ = nr_threads;
169  };
170 
171  /** \return the number of threads used if OpenMP is activated. */
172  inline int
174  {
175  return (nr_threads_);
176  };
177 
178  /** \brief Set the constant factor delta which weights the internally calculated
179  * parameters. \param[in] delta the weight factor delta \param[in] normalize flag if
180  * delta should be normalized according to point cloud density
181  */
182  inline void
183  setDelta(float delta, bool normalize = false)
184  {
185  delta_ = delta;
186  normalize_delta_ = normalize;
187  };
188 
189  /** \return the constant factor delta which weights the internally calculated
190  * parameters. */
191  inline float
192  getDelta() const
193  {
194  return (delta_);
195  };
196 
197  /** \brief Set the approximate overlap between source and target.
198  * \param[in] approx_overlap the estimated overlap
199  */
200  inline void
201  setApproxOverlap(float approx_overlap)
202  {
203  approx_overlap_ = approx_overlap;
204  };
205 
206  /** \return the approximated overlap between source and target. */
207  inline float
209  {
210  return (approx_overlap_);
211  };
212 
213  /** \brief Set the scoring threshold used for early finishing the method.
214  * \param[in] score_threshold early terminating score criteria
215  */
216  inline void
217  setScoreThreshold(float score_threshold)
218  {
219  score_threshold_ = score_threshold;
220  };
221 
222  /** \return the scoring threshold used for early finishing the method. */
223  inline float
225  {
226  return (score_threshold_);
227  };
228 
229  /** \brief Set the number of source samples to use during alignment.
230  * \param[in] nr_samples the number of source samples
231  */
232  inline void
233  setNumberOfSamples(int nr_samples)
234  {
235  nr_samples_ = nr_samples;
236  };
237 
238  /** \return the number of source samples to use during alignment. */
239  inline int
241  {
242  return (nr_samples_);
243  };
244 
245  /** \brief Set the maximum normal difference between valid point correspondences in
246  * degree. \param[in] max_norm_diff the maximum difference in degree
247  */
248  inline void
249  setMaxNormalDifference(float max_norm_diff)
250  {
251  max_norm_diff_ = max_norm_diff;
252  };
253 
254  /** \return the maximum normal difference between valid point correspondences in
255  * degree. */
256  inline float
258  {
259  return (max_norm_diff_);
260  };
261 
262  /** \brief Set the maximum computation time in seconds.
263  * \param[in] max_runtime the maximum runtime of the method in seconds
264  */
265  inline void
266  setMaxComputationTime(int max_runtime)
267  {
268  max_runtime_ = max_runtime;
269  };
270 
271  /** \return the maximum computation time in seconds. */
272  inline int
274  {
275  return (max_runtime_);
276  };
277 
278  /** \return the fitness score of the best scored four-point match. */
279  inline float
281  {
282  return (fitness_score_);
283  };
284 
285 protected:
289 
300 
301  /** \brief Rigid transformation computation method.
302  * \param output the transformed input point cloud dataset using the rigid
303  * transformation found \param guess The computed transforamtion
304  */
305  void
307  const Eigen::Matrix4f& guess) override;
308 
309  /** \brief Internal computation initialization. */
310  virtual bool
311  initCompute();
312 
313  /** \brief Select an approximately coplanar set of four points from the source cloud.
314  * \param[out] base_indices selected source cloud indices, further used as base (B)
315  * \param[out] ratio the two diagonal intersection ratios (r1,r2) of the base points
316  * \return
317  * * < 0 no coplanar four point sets with large enough sampling distance was found
318  * * = 0 a set of four congruent points was selected
319  */
320  int
321  selectBase(pcl::Indices& base_indices, float (&ratio)[2]);
322 
323  /** \brief Select randomly a triplet of points with large point-to-point distances.
324  * The minimum point sampling distance is calculated based on the estimated point
325  * cloud overlap during initialization.
326  *
327  * \param[out] base_indices indices of base B
328  * \return
329  * * < 0 no triangle with large enough base lines could be selected
330  * * = 0 base triangle successfully selected
331  */
332  int
333  selectBaseTriangle(pcl::Indices& base_indices);
334 
335  /** \brief Setup the base (four coplanar points) by ordering the points and computing
336  * intersection ratios and segment to segment distances of base diagonal.
337  *
338  * \param[in,out] base_indices indices of base B (will be reordered)
339  * \param[out] ratio diagonal intersection ratios of base points
340  */
341  void
342  setupBase(pcl::Indices& base_indices, float (&ratio)[2]);
343 
344  /** \brief Calculate intersection ratios and segment to segment distances of base
345  * diagonals. \param[in] base_indices indices of base B \param[out] ratio diagonal
346  * intersection ratios of base points \return quality value of diagonal intersection
347  */
348  float
349  segmentToSegmentDist(const pcl::Indices& base_indices, float (&ratio)[2]);
350 
351  /** \brief Search for corresponding point pairs given the distance between two base
352  * points.
353  *
354  * \param[in] idx1 first index of current base segment (in source cloud)
355  * \param[in] idx2 second index of current base segment (in source cloud)
356  * \param[out] pairs resulting point pairs with point-to-point distance close to
357  * ref_dist \return
358  * * < 0 no corresponding point pair was found
359  * * = 0 at least one point pair candidate was found
360  */
361  virtual int
362  bruteForceCorrespondences(int idx1, int idx2, pcl::Correspondences& pairs);
363 
364  /** \brief Determine base matches by combining the point pair candidate and search for
365  * coinciding intersection points using the diagonal segment ratios of base B. The
366  * coincidation threshold is calculated during initialization (coincidation_limit_).
367  *
368  * \param[in] base_indices indices of base B
369  * \param[out] matches vector of candidate matches w.r.t the base B
370  * \param[in] pairs_a point pairs corresponding to points of 1st diagonal of base B
371  * \param[in] pairs_b point pairs corresponding to points of 2nd diagonal of base B
372  * \param[in] ratio diagonal intersection ratios of base points
373  * \return
374  * * < 0 no base match could be found
375  * * = 0 at least one base match was found
376  */
377  virtual int
378  determineBaseMatches(const pcl::Indices& base_indices,
379  std::vector<pcl::Indices>& matches,
380  const pcl::Correspondences& pairs_a,
381  const pcl::Correspondences& pairs_b,
382  const float (&ratio)[2]);
383 
384  /** \brief Check if outer rectangle distance of matched points fit with the base
385  * rectangle.
386  *
387  * \param[in] match_indices indices of match M
388  * \param[in] ds edge lengths of base B
389  * \return
390  * * < 0 at least one edge of the match M has no corresponding one in the base B
391  * * = 0 edges of match M fits to the ones of base B
392  */
393  int
394  checkBaseMatch(const pcl::Indices& match_indices, const float (&ds)[4]);
395 
396  /** \brief Method to handle current candidate matches. Here we validate and evaluate
397  * the matches w.r.t the base and store the best fitting match (together with its
398  * score and estimated transformation). \note For forwards compatibility the results
399  * are stored in 'vectors of size 1'.
400  *
401  * \param[in] base_indices indices of base B
402  * \param[in,out] matches vector of candidate matches w.r.t the base B. The candidate
403  * matches are reordered during this step. \param[out] candidates vector which
404  * contains the candidates matches M
405  */
406  virtual void
407  handleMatches(const pcl::Indices& base_indices,
408  std::vector<pcl::Indices>& matches,
409  MatchingCandidates& candidates);
410 
411  /** \brief Sets the correspondences between the base B and the match M by using the
412  * distance of each point to the centroid of the rectangle.
413  *
414  * \param[in] base_indices indices of base B
415  * \param[in] match_indices indices of match M
416  * \param[out] correspondences resulting correspondences
417  */
418  virtual void
419  linkMatchWithBase(const pcl::Indices& base_indices,
420  pcl::Indices& match_indices,
421  pcl::Correspondences& correspondences);
422 
423  /** \brief Validate the matching by computing the transformation between the source
424  * and target based on the four matched points and by comparing the mean square error
425  * (MSE) to a threshold. The MSE limit was calculated during initialization
426  * (max_mse_).
427  *
428  * \param[in] base_indices indices of base B
429  * \param[in] match_indices indices of match M
430  * \param[in] correspondences correspondences between source and target
431  * \param[out] transformation resulting transformation matrix
432  * \return
433  * * < 0 MSE bigger than max_mse_
434  * * = 0 MSE smaller than max_mse_
435  */
436  virtual int
437  validateMatch(const pcl::Indices& base_indices,
438  const pcl::Indices& match_indices,
439  const pcl::Correspondences& correspondences,
440  Eigen::Matrix4f& transformation);
441 
442  /** \brief Validate the transformation by calculating the number of inliers after
443  * transforming the source cloud. The resulting fitness score is later used as the
444  * decision criteria of the best fitting match.
445  *
446  * \param[out] transformation updated orientation matrix using all inliers
447  * \param[out] fitness_score current best fitness_score
448  * \note fitness score is only updated if the score of the current transformation
449  * exceeds the input one. \return
450  * * < 0 if previous result is better than the current one (score remains)
451  * * = 0 current result is better than the previous one (score updated)
452  */
453  virtual int
454  validateTransformation(Eigen::Matrix4f& transformation, float& fitness_score);
455 
456  /** \brief Final computation of best match out of vector of best matches. To avoid
457  * cross thread dependencies during parallel running, a best match for each try was
458  * calculated. \note For forwards compatibility the candidates are stored in vectors
459  * of 'vectors of size 1'. \param[in] candidates vector of candidate matches
460  */
461  virtual void
462  finalCompute(const std::vector<MatchingCandidates>& candidates);
463 
464  /** \brief Normals of source point cloud. */
465  NormalsConstPtr source_normals_;
466 
467  /** \brief Normals of target point cloud. */
468  NormalsConstPtr target_normals_;
469 
470  /** \brief Number of threads for parallelization (standard = 1).
471  * \note Only used if run compiled with OpenMP.
472  */
473  int nr_threads_{1};
474 
475  /** \brief Estimated overlap between source and target (standard = 0.5). */
476  float approx_overlap_{0.5f};
477 
478  /** \brief Delta value of 4pcs algorithm (standard = 1.0).
479  * It can be used as:
480  * * absolute value (normalization = false), value should represent the point accuracy
481  * to ensure finding neighbors between source <-> target
482  * * relative value (normalization = true), to adjust the internally calculated point
483  * accuracy (= point density)
484  */
485  float delta_{1.f};
486 
487  /** \brief Score threshold to stop calculation with success.
488  * If not set by the user it depends on the size of the approximated overlap
489  */
491 
492  /** \brief The number of points to uniformly sample the source point cloud. (standard
493  * = 0 => full cloud). */
494  int nr_samples_{0};
495 
496  /** \brief Maximum normal difference of corresponding point pairs in degrees (standard
497  * = 90). */
498  float max_norm_diff_{90.f};
499 
500  /** \brief Maximum allowed computation time in seconds (standard = 0 => ~unlimited).
501  */
502  int max_runtime_{0};
503 
504  /** \brief Resulting fitness score of the best match. */
506 
507  /** \brief Estimated diameter of the target point cloud. */
508  float diameter_{0.0f};
509 
510  /** \brief Estimated squared metric overlap between source and target.
511  * \note Internally calculated using the estimated overlap and the extent of the
512  * source cloud. It is used to derive the minimum sampling distance of the base points
513  * as well as to calculated the number of tries to reliably find a correct match.
514  */
516 
517  /** \brief Use normals flag. */
518  bool use_normals_{false};
519 
520  /** \brief Normalize delta flag. */
521  bool normalize_delta_{true};
522 
523  /** \brief A pointer to the vector of source point indices to use after sampling. */
525 
526  /** \brief A pointer to the vector of target point indices to use after sampling. */
528 
529  /** \brief Maximal difference between corresponding point pairs in source and target.
530  * \note Internally calculated using an estimation of the point density.
531  */
532  float max_pair_diff_{0.0f};
533 
534  /** \brief Maximal difference between the length of the base edges and valid match
535  * edges. \note Internally calculated using an estimation of the point density.
536  */
537  float max_edge_diff_{0.0f};
538 
539  /** \brief Maximal distance between coinciding intersection points to find valid
540  * matches. \note Internally calculated using an estimation of the point density.
541  */
542  float coincidation_limit_{0.0f};
543 
544  /** \brief Maximal mean squared errors of a transformation calculated from a candidate
545  * match. \note Internally calculated using an estimation of the point density.
546  */
547  float max_mse_{0.0f};
548 
549  /** \brief Maximal squared point distance between source and target points to count as
550  * inlier. \note Internally calculated using an estimation of the point density.
551  */
552  float max_inlier_dist_sqr_{0.0f};
553 
554  /** \brief Definition of a small error. */
555  const float small_error_{0.00001f};
556 };
557 }; // namespace registration
558 }; // namespace pcl
559 
560 #include <pcl/registration/impl/ia_fpcs.hpp>
PCL base class.
Definition: pcl_base.h:70
typename VectorType::iterator iterator
Definition: point_cloud.h:425
shared_ptr< PointCloud< PointSource > > Ptr
Definition: point_cloud.h:413
shared_ptr< const PointCloud< PointT > > ConstPtr
Definition: point_cloud.h:414
Registration represents the base registration class for general purpose, ICP-like methods.
Definition: registration.h:57
typename KdTreeReciprocal::Ptr KdTreeReciprocalPtr
Definition: registration.h:74
shared_ptr< const Registration< PointSource, PointTarget, float > > ConstPtr
Definition: registration.h:67
pcl::PointCloud< PointSource > PointCloudSource
Definition: registration.h:76
typename PointCloudSource::Ptr PointCloudSourcePtr
Definition: registration.h:77
shared_ptr< Registration< PointSource, PointTarget, float > > Ptr
Definition: registration.h:66
FPCSInitialAlignment computes corresponding four point congruent sets as described in: "4-points cong...
Definition: ia_fpcs.h:81
virtual void finalCompute(const std::vector< MatchingCandidates > &candidates)
Final computation of best match out of vector of best matches.
Definition: ia_fpcs.hpp:878
void setTargetNormals(const NormalsConstPtr &target_normals)
Provide a pointer to the normals of the target point cloud.
Definition: ia_fpcs.h:150
void setupBase(pcl::Indices &base_indices, float(&ratio)[2])
Setup the base (four coplanar points) by ordering the points and computing intersection ratios and se...
Definition: ia_fpcs.hpp:425
bool use_normals_
Use normals flag.
Definition: ia_fpcs.h:518
int selectBaseTriangle(pcl::Indices &base_indices)
Select randomly a triplet of points with large point-to-point distances.
Definition: ia_fpcs.hpp:387
float max_edge_diff_
Maximal difference between the length of the base edges and valid match edges.
Definition: ia_fpcs.h:537
virtual int bruteForceCorrespondences(int idx1, int idx2, pcl::Correspondences &pairs)
Search for corresponding point pairs given the distance between two base points.
Definition: ia_fpcs.hpp:553
float delta_
Delta value of 4pcs algorithm (standard = 1.0).
Definition: ia_fpcs.h:485
int selectBase(pcl::Indices &base_indices, float(&ratio)[2])
Select an approximately coplanar set of four points from the source cloud.
Definition: ia_fpcs.hpp:321
void setNumberOfSamples(int nr_samples)
Set the number of source samples to use during alignment.
Definition: ia_fpcs.h:233
float max_base_diameter_sqr_
Estimated squared metric overlap between source and target.
Definition: ia_fpcs.h:515
float coincidation_limit_
Maximal distance between coinciding intersection points to find valid matches.
Definition: ia_fpcs.h:542
virtual int validateTransformation(Eigen::Matrix4f &transformation, float &fitness_score)
Validate the transformation by calculating the number of inliers after transforming the source cloud.
Definition: ia_fpcs.hpp:836
virtual int determineBaseMatches(const pcl::Indices &base_indices, std::vector< pcl::Indices > &matches, const pcl::Correspondences &pairs_a, const pcl::Correspondences &pairs_b, const float(&ratio)[2])
Determine base matches by combining the point pair candidate and search for coinciding intersection p...
Definition: ia_fpcs.hpp:607
virtual void linkMatchWithBase(const pcl::Indices &base_indices, pcl::Indices &match_indices, pcl::Correspondences &correspondences)
Sets the correspondences between the base B and the match M by using the distance of each point to th...
Definition: ia_fpcs.hpp:751
virtual void handleMatches(const pcl::Indices &base_indices, std::vector< pcl::Indices > &matches, MatchingCandidates &candidates)
Method to handle current candidate matches.
Definition: ia_fpcs.hpp:713
float max_inlier_dist_sqr_
Maximal squared point distance between source and target points to count as inlier.
Definition: ia_fpcs.h:552
bool normalize_delta_
Normalize delta flag.
Definition: ia_fpcs.h:521
void setScoreThreshold(float score_threshold)
Set the scoring threshold used for early finishing the method.
Definition: ia_fpcs.h:217
NormalsConstPtr target_normals_
Normals of target point cloud.
Definition: ia_fpcs.h:468
NormalsConstPtr source_normals_
Normals of source point cloud.
Definition: ia_fpcs.h:465
pcl::IndicesPtr target_indices_
A pointer to the vector of target point indices to use after sampling.
Definition: ia_fpcs.h:527
void setMaxNormalDifference(float max_norm_diff)
Set the maximum normal difference between valid point correspondences in degree.
Definition: ia_fpcs.h:249
float max_mse_
Maximal mean squared errors of a transformation calculated from a candidate match.
Definition: ia_fpcs.h:547
int checkBaseMatch(const pcl::Indices &match_indices, const float(&ds)[4])
Check if outer rectangle distance of matched points fit with the base rectangle.
Definition: ia_fpcs.hpp:689
int nr_samples_
The number of points to uniformly sample the source point cloud.
Definition: ia_fpcs.h:494
float approx_overlap_
Estimated overlap between source and target (standard = 0.5).
Definition: ia_fpcs.h:476
pcl::IndicesPtr source_indices_
A pointer to the vector of source point indices to use after sampling.
Definition: ia_fpcs.h:524
float segmentToSegmentDist(const pcl::Indices &base_indices, float(&ratio)[2])
Calculate intersection ratios and segment to segment distances of base diagonals.
Definition: ia_fpcs.hpp:468
int nr_threads_
Number of threads for parallelization (standard = 1).
Definition: ia_fpcs.h:473
virtual int validateMatch(const pcl::Indices &base_indices, const pcl::Indices &match_indices, const pcl::Correspondences &correspondences, Eigen::Matrix4f &transformation)
Validate the matching by computing the transformation between the source and target based on the four...
Definition: ia_fpcs.hpp:804
IndicesPtr getTargetIndices() const
Definition: ia_fpcs.h:125
float max_norm_diff_
Maximum normal difference of corresponding point pairs in degrees (standard = 90).
Definition: ia_fpcs.h:498
float fitness_score_
Resulting fitness score of the best match.
Definition: ia_fpcs.h:505
float diameter_
Estimated diameter of the target point cloud.
Definition: ia_fpcs.h:508
void setSourceNormals(const NormalsConstPtr &source_normals)
Provide a pointer to the normals of the source point cloud.
Definition: ia_fpcs.h:134
NormalsConstPtr getSourceNormals() const
Definition: ia_fpcs.h:141
NormalsConstPtr getTargetNormals() const
Definition: ia_fpcs.h:157
void setMaxComputationTime(int max_runtime)
Set the maximum computation time in seconds.
Definition: ia_fpcs.h:266
void setTargetIndices(const IndicesPtr &target_indices)
Provide a pointer to the vector of target indices.
Definition: ia_fpcs.h:118
void setNumberOfThreads(int nr_threads)
Set the number of used threads if OpenMP is activated.
Definition: ia_fpcs.h:166
float max_pair_diff_
Maximal difference between corresponding point pairs in source and target.
Definition: ia_fpcs.h:532
void setApproxOverlap(float approx_overlap)
Set the approximate overlap between source and target.
Definition: ia_fpcs.h:201
~FPCSInitialAlignment() override=default
Destructor.
const float small_error_
Definition of a small error.
Definition: ia_fpcs.h:555
int max_runtime_
Maximum allowed computation time in seconds (standard = 0 => ~unlimited).
Definition: ia_fpcs.h:502
void computeTransformation(PointCloudSource &output, const Eigen::Matrix4f &guess) override
Rigid transformation computation method.
Definition: ia_fpcs.hpp:141
float score_threshold_
Score threshold to stop calculation with success.
Definition: ia_fpcs.h:490
void setDelta(float delta, bool normalize=false)
Set the constant factor delta which weights the internally calculated parameters.
Definition: ia_fpcs.h:183
virtual bool initCompute()
Internal computation initialization.
Definition: ia_fpcs.hpp:214
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 standard C methods and C++ classes that are common to all methods.
std::vector< MatchingCandidate, Eigen::aligned_allocator< MatchingCandidate > > MatchingCandidates
float getMeanPointDensity(const typename pcl::PointCloud< PointT >::ConstPtr &cloud, float max_dist, int nr_threads=1)
Compute the mean point density of a given point cloud.
Definition: ia_fpcs.hpp:53
std::vector< pcl::Correspondence, Eigen::aligned_allocator< pcl::Correspondence > > Correspondences
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:133
shared_ptr< Indices > IndicesPtr
Definition: pcl_base.h:58
A point structure representing normal coordinates and the surface curvature estimate.
Container for matching candidate consisting of.