ACloudViewer  3.9.4
A Modern Library for 3D Data Processing
FastGlobalRegistration.cpp
Go to the documentation of this file.
1 // ----------------------------------------------------------------------------
2 // - CloudViewer: www.cloudViewer.org -
3 // ----------------------------------------------------------------------------
4 // Copyright (c) 2018-2024 www.cloudViewer.org
5 // SPDX-License-Identifier: MIT
6 // ----------------------------------------------------------------------------
7 
9 
10 #include <Helper.h>
11 #include <Logging.h>
12 #include <ecvFeature.h>
13 #include <ecvKDTreeFlann.h>
14 #include <ecvPointCloud.h>
15 
17 #include "pipelines/registration/Registration.h"
18 
19 namespace cloudViewer {
20 namespace pipelines {
21 namespace registration {
22 
23 static std::vector<std::pair<int, int>> InitialMatching(
24  const utility::Feature& src_features,
25  const utility::Feature& dst_features) {
26  geometry::KDTreeFlann src_feature_tree(src_features);
27  geometry::KDTreeFlann dst_feature_tree(dst_features);
28  std::map<int, int> corres_ij;
29  std::vector<int> corres_ji(dst_features.data_.cols(), -1);
30 
31 #pragma omp for nowait
32  for (int j = 0; j < dst_features.data_.cols(); j++) {
33  std::vector<int> corres_tmp(1);
34  std::vector<double> dist_tmp(1);
35  src_feature_tree.SearchKNN(Eigen::VectorXd(dst_features.data_.col(j)),
36  1, corres_tmp, dist_tmp);
37  int i = corres_tmp[0];
38  corres_ji[j] = i;
39  if (corres_ij.find(i) == corres_ij.end()) {
40  // set a temp value to prevent other threads recomputing
41  // corres_ij[i] until the following dst_feature_tree.SearchKNN()
42  // call completes. There is still a race condition but the result
43  // would be fine since both threads will compute the same result
44  corres_ij[i] = -1;
45  dst_feature_tree.SearchKNN(
46  Eigen::VectorXd(src_features.data_.col(i)), 1, corres_tmp,
47  dist_tmp);
48  corres_ij[i] = corres_tmp[0];
49  }
50  }
51 
52  utility::LogDebug("\t[cross check] ");
53  std::vector<std::pair<int, int>> corres_cross;
54  for (const std::pair<const int, int>& ij : corres_ij) {
55  if (corres_ji[ij.second] == ij.first) corres_cross.push_back(ij);
56  }
57  utility::LogDebug("Initial matchings : {}", corres_cross.size());
58  return corres_cross;
59 }
60 
61 static std::vector<std::pair<int, int>> AdvancedMatching(
62  const ccPointCloud& src_point_cloud,
63  const ccPointCloud& dst_point_cloud,
64  const std::vector<std::pair<int, int>>& corres_cross,
65  const FastGlobalRegistrationOption& option) {
66  utility::LogDebug("\t[tuple constraint] ");
67  int rand0, rand1, rand2, i, cnt = 0;
68  int idi0, idi1, idi2, idj0, idj1, idj2;
69  double scale = option.tuple_scale_;
70  int ncorr = static_cast<int>(corres_cross.size());
71  int number_of_trial = ncorr * 100;
72 
73  if (ncorr <= 2) {
75  "Not enough correspondences for tuple test. At least 3 needed, "
76  "got {}.",
77  ncorr);
78  return {};
79  }
80 
81  utility::random::UniformIntGenerator<int> rand_generator(0, ncorr - 1);
82  std::vector<std::pair<int, int>> corres_tuple;
83  for (i = 0; i < number_of_trial; i++) {
84  rand0 = rand_generator();
85  rand1 = rand_generator();
86  rand2 = rand_generator();
87  idi0 = corres_cross[rand0].first;
88  idj0 = corres_cross[rand0].second;
89  idi1 = corres_cross[rand1].first;
90  idj1 = corres_cross[rand1].second;
91  idi2 = corres_cross[rand2].first;
92  idj2 = corres_cross[rand2].second;
93 
94  // collect 3 points from source fragment
95  Eigen::Vector3d pti0 = src_point_cloud.getEigenPoint(idi0);
96  Eigen::Vector3d pti1 = src_point_cloud.getEigenPoint(idi1);
97  Eigen::Vector3d pti2 = src_point_cloud.getEigenPoint(idi2);
98  double li0 = (pti0 - pti1).norm();
99  double li1 = (pti1 - pti2).norm();
100  double li2 = (pti2 - pti0).norm();
101 
102  // collect 3 points from dest fragment
103  Eigen::Vector3d ptj0 = dst_point_cloud.getEigenPoint(idj0);
104  Eigen::Vector3d ptj1 = dst_point_cloud.getEigenPoint(idj1);
105  Eigen::Vector3d ptj2 = dst_point_cloud.getEigenPoint(idj2);
106  double lj0 = (ptj0 - ptj1).norm();
107  double lj1 = (ptj1 - ptj2).norm();
108  double lj2 = (ptj2 - ptj0).norm();
109 
110  // check tuple constraint
111  if ((li0 * scale < lj0) && (lj0 < li0 / scale) && (li1 * scale < lj1) &&
112  (lj1 < li1 / scale) && (li2 * scale < lj2) && (lj2 < li2 / scale)) {
113  corres_tuple.push_back(std::pair<int, int>(idi0, idj0));
114  corres_tuple.push_back(std::pair<int, int>(idi1, idj1));
115  corres_tuple.push_back(std::pair<int, int>(idi2, idj2));
116  cnt++;
117  }
118  if (cnt >= option.maximum_tuple_count_) break;
119  }
120  utility::LogDebug("{:d} tuples ({:d} trial, {:d} actual).", cnt,
121  number_of_trial, i);
122 
123  utility::LogDebug("\t[final] matches {:d}.", (int)corres_tuple.size());
124  return corres_tuple;
125 }
126 
127 // Normalize scale of points. X' = (X-\mu)/scale
128 std::tuple<std::vector<Eigen::Vector3d>, double, double> NormalizePointCloud(
129  std::vector<ccPointCloud>& point_cloud_vec,
130  const FastGlobalRegistrationOption& option) {
131  int num = 2;
132  double scale = 0;
133  std::vector<Eigen::Vector3d> pcd_mean_vec;
134  double scale_global, scale_start;
135 
136  for (int i = 0; i < num; ++i) {
137  double max_scale = 0.0;
138  Eigen::Vector3d mean;
139  mean.setZero();
140 
141  int npti = static_cast<int>(point_cloud_vec[i].size());
142  for (int ii = 0; ii < npti; ++ii)
143  mean = mean +
144  point_cloud_vec[i].getEigenPoint(static_cast<size_t>(ii));
145  mean = mean / npti;
146  pcd_mean_vec.push_back(mean);
147 
148  utility::LogDebug("normalize points :: mean = [{:f} {:f} {:f}]",
149  mean(0), mean(1), mean(2));
150  for (int ii = 0; ii < npti; ++ii)
151  *point_cloud_vec[i].getPointPtr(static_cast<size_t>(ii)) -= mean;
152 
153  for (int ii = 0; ii < npti; ++ii) {
154  Eigen::Vector3d p(
155  point_cloud_vec[i].getEigenPoint(static_cast<size_t>(ii)));
156  double temp = p.norm();
157  if (temp > max_scale) max_scale = temp;
158  }
159  if (max_scale > scale) scale = max_scale;
160  }
161 
162  if (option.use_absolute_scale_) {
163  scale_global = 1.0;
164  scale_start = scale;
165  } else {
166  scale_global = scale;
167  scale_start = 1.0;
168  }
169  utility::LogDebug("normalize points :: global scale : {:f}", scale_global);
170  if (scale_global <= 0) {
171  utility::LogError("Invalid scale_global: {}, it must be > 0.",
172  scale_global);
173  }
174 
175  for (int i = 0; i < num; ++i) {
176  int npti = static_cast<int>(point_cloud_vec[i].size());
177  for (int ii = 0; ii < npti; ++ii) {
178  *point_cloud_vec[i].getPointPtr(static_cast<size_t>(ii)) /=
179  static_cast<float>(scale_global);
180  }
181  }
182  return std::make_tuple(pcd_mean_vec, scale_global, scale_start);
183 }
184 
186  const std::vector<ccPointCloud>& point_cloud_vec,
187  const std::vector<std::pair<int, int>>& corres,
188  double scale_start,
189  const FastGlobalRegistrationOption& option) {
190  utility::LogDebug("Pairwise rigid pose optimization");
191  double par = scale_start;
192  int numIter = option.iteration_number_;
193 
194  int i = 0, j = 1;
195  ccPointCloud point_cloud_copy_j = point_cloud_vec[j];
196 
197  if (corres.size() < 10) return Eigen::Matrix4d::Identity();
198 
199  std::vector<double> s(corres.size(), 1.0);
200  Eigen::Matrix4d trans;
201  trans.setIdentity();
202 
203  for (int itr = 0; itr < numIter; itr++) {
204  const int nvariable = 6;
205  Eigen::MatrixXd JTJ(nvariable, nvariable);
206  Eigen::MatrixXd JTr(nvariable, 1);
207  Eigen::MatrixXd J(nvariable, 1);
208  JTJ.setZero();
209  JTr.setZero();
210  double r = 0.0, r2 = 0.0;
211 
212  for (size_t c = 0; c < corres.size(); c++) {
213  int ii = corres[c].first;
214  int jj = corres[c].second;
215  Eigen::Vector3d p, q;
216  p = point_cloud_vec[i].getEigenPoint(static_cast<size_t>(ii));
217  q = point_cloud_copy_j.getEigenPoint(static_cast<size_t>(jj));
218  Eigen::Vector3d rpq = p - q;
219 
220  size_t c2 = c;
221  double temp = par / (rpq.dot(rpq) + par);
222  s[c2] = temp * temp;
223 
224  J.setZero();
225  J(1) = -q(2);
226  J(2) = q(1);
227  J(3) = -1;
228  r = rpq(0);
229  JTJ += J * J.transpose() * s[c2];
230  JTr += J * r * s[c2];
231  r2 += r * r * s[c2];
232 
233  J.setZero();
234  J(2) = -q(0);
235  J(0) = q(2);
236  J(4) = -1;
237  r = rpq(1);
238  JTJ += J * J.transpose() * s[c2];
239  JTr += J * r * s[c2];
240  r2 += r * r * s[c2];
241 
242  J.setZero();
243  J(0) = -q(1);
244  J(1) = q(0);
245  J(5) = -1;
246  r = rpq(2);
247  JTJ += J * J.transpose() * s[c2];
248  JTr += J * r * s[c2];
249  r2 += r * r * s[c2];
250  r2 += (par * (1.0 - sqrt(s[c2])) * (1.0 - sqrt(s[c2])));
251  }
252  bool success;
253  Eigen::VectorXd result;
254  std::tie(success, result) = utility::SolveLinearSystemPSD(-JTJ, JTr);
255  Eigen::Matrix4d delta = utility::TransformVector6dToMatrix4d(result);
256  trans = delta * trans;
257  point_cloud_copy_j.Transform(delta);
258 
259  // graduated non-convexity.
260  if (option.decrease_mu_) {
261  if (itr % 4 == 0 && par > option.maximum_correspondence_distance_) {
262  par /= option.division_factor_;
263  }
264  }
265  }
266  return trans;
267 }
268 
269 // Below line indicates how the transformation matrix aligns two point clouds
270 // e.g. T * point_cloud_vec[1] is aligned with point_cloud_vec[0].
272  const Eigen::Matrix4d& transformation,
273  const std::vector<Eigen::Vector3d>& pcd_mean_vec,
274  const double scale_global) {
275  Eigen::Matrix3d R = transformation.block<3, 3>(0, 0);
276  Eigen::Vector3d t = transformation.block<3, 1>(0, 3);
277  Eigen::Matrix4d transtemp = Eigen::Matrix4d::Zero();
278  transtemp.block<3, 3>(0, 0) = R;
279  transtemp.block<3, 1>(0, 3) =
280  -R * pcd_mean_vec[1] + t * scale_global + pcd_mean_vec[0];
281  transtemp(3, 3) = 1;
282  return transtemp;
283 }
284 
286  const ccPointCloud &source,
287  const ccPointCloud &target,
288  const CorrespondenceSet &corres,
289  const FastGlobalRegistrationOption &option /* =
290  FastGlobalRegistrationOption()*/) {
291  ccPointCloud source_orig = source;
292  ccPointCloud target_orig = target;
293 
294  std::vector<ccPointCloud> point_cloud_vec;
295  point_cloud_vec.push_back(source);
296  point_cloud_vec.push_back(target);
297 
298  double scale_global, scale_start;
299  std::vector<Eigen::Vector3d> pcd_mean_vec;
300  std::tie(pcd_mean_vec, scale_global, scale_start) =
301  NormalizePointCloud(point_cloud_vec, option);
302 
303  std::vector<std::pair<int, int>> corresvec;
304  corresvec.reserve(corres.size());
305  for (size_t i = 0; i < corres.size(); ++i) {
306  corresvec.push_back({corres[i](0), corres[i](1)});
307  }
308 
309  if (option.tuple_test_) {
310  corresvec = AdvancedMatching(source, target, corresvec, option);
311  }
312 
313  Eigen::Matrix4d transformation;
314  transformation = OptimizePairwiseRegistration(point_cloud_vec, corresvec,
315  scale_global, option);
316 
317  // as the original code T * point_cloud_vec[1] is aligned with
318  // point_cloud_vec[0] matrix inverse is applied here.
319  return EvaluateRegistration(
320  source_orig, target_orig, option.maximum_correspondence_distance_,
321  GetTransformationOriginalScale(transformation, pcd_mean_vec,
322  scale_global)
323  .inverse());
324 }
325 
327  const ccPointCloud& source,
328  const ccPointCloud& target,
329  const utility::Feature& source_feature,
330  const utility::Feature& target_feature,
331  const FastGlobalRegistrationOption& option /* =
332  FastGlobalRegistrationOption()*/) {
333  ccPointCloud source_orig = source;
334  ccPointCloud target_orig = target;
335 
336  std::vector<ccPointCloud> point_cloud_vec;
337  point_cloud_vec.push_back(source);
338  point_cloud_vec.push_back(target);
339 
340  double scale_global, scale_start;
341  std::vector<Eigen::Vector3d> pcd_mean_vec;
342  std::tie(pcd_mean_vec, scale_global, scale_start) =
343  NormalizePointCloud(point_cloud_vec, option);
344 
345  std::vector<std::pair<int, int>> corres;
346  if (option.tuple_test_) {
347  // use the smaller point cloud as the query during knn search
348  if (source.size() >= target.size()) {
349  corres = AdvancedMatching(
350  source, target,
351  InitialMatching(source_feature, target_feature), option);
352  } else {
353  corres = AdvancedMatching(
354  target, source,
355  InitialMatching(target_feature, source_feature), option);
356  for (auto& p : corres) std::swap(p.first, p.second);
357  }
358  } else {
359  corres = InitialMatching(source_feature, target_feature);
360  }
361 
362  Eigen::Matrix4d transformation;
363  transformation = OptimizePairwiseRegistration(point_cloud_vec, corres,
364  scale_global, option);
365 
366  // as the original code T * point_cloud_vec[1] is aligned with
367  // point_cloud_vec[0] matrix inverse is applied here.
368  return EvaluateRegistration(
369  source_orig, target_orig, option.maximum_correspondence_distance_,
370  GetTransformationOriginalScale(transformation, pcd_mean_vec,
371  scale_global)
372  .inverse());
373 }
374 
375 } // namespace registration
376 } // namespace pipelines
377 } // namespace cloudViewer
core::Tensor result
Definition: VtkUtils.cpp:76
A 3D cloud and its associated features (color, normals, scalar fields, etc.)
virtual ccPointCloud & Transform(const Eigen::Matrix4d &trans) override
Apply transformation (4x4 matrix) to the geometry coordinates.
unsigned size() const override
Definition: PointCloudTpl.h:38
Eigen::Vector3d getEigenPoint(size_t index) const
KDTree with FLANN for nearest neighbor search.
int SearchKNN(const T &query, int knn, std::vector< int > &indices, std::vector< double > &distance2) const
double tuple_scale_
Similarity measure used for tuples of feature points.
double division_factor_
Division factor used for graduated non-convexity.
Class to store featrues for registration.
Definition: ecvFeature.h:29
Eigen::MatrixXd data_
Data buffer storing features.
Definition: ecvFeature.h:54
#define LogWarning(...)
Definition: Logging.h:72
#define LogError(...)
Definition: Logging.h:60
#define LogDebug(...)
Definition: Logging.h:90
Helper functions for the ml ops.
Eigen::Matrix4d OptimizePairwiseRegistration(const std::vector< ccPointCloud > &point_cloud_vec, const std::vector< std::pair< int, int >> &corres, double scale_start, const FastGlobalRegistrationOption &option)
Eigen::Matrix4d GetTransformationOriginalScale(const Eigen::Matrix4d &transformation, const std::vector< Eigen::Vector3d > &pcd_mean_vec, const double scale_global)
std::vector< Eigen::Vector2i > CorrespondenceSet
RegistrationResult FastGlobalRegistrationBasedOnFeatureMatching(const ccPointCloud &source, const ccPointCloud &target, const utility::Feature &source_feature, const utility::Feature &target_feature, const FastGlobalRegistrationOption &option)
Fast Global Registration based on a given set of FPFH features.
static std::vector< std::pair< int, int > > AdvancedMatching(const ccPointCloud &src_point_cloud, const ccPointCloud &dst_point_cloud, const std::vector< std::pair< int, int >> &corres_cross, const FastGlobalRegistrationOption &option)
std::tuple< std::vector< Eigen::Vector3d >, double, double > NormalizePointCloud(std::vector< ccPointCloud > &point_cloud_vec, const FastGlobalRegistrationOption &option)
static std::vector< std::pair< int, int > > InitialMatching(const utility::Feature &src_features, const utility::Feature &dst_features)
RegistrationResult FastGlobalRegistrationBasedOnCorrespondence(const ccPointCloud &source, const ccPointCloud &target, const CorrespondenceSet &corres, const FastGlobalRegistrationOption &option)
Fast Global Registration based on a given set of correspondences.
RegistrationResult EvaluateRegistration(const ccPointCloud &source, const ccPointCloud &target, double max_correspondence_distance, const Eigen::Matrix4d &transformation)
Function for evaluating registration between point clouds.
std::tuple< bool, Eigen::VectorXd > SolveLinearSystemPSD(const Eigen::MatrixXd &A, const Eigen::VectorXd &b, bool prefer_sparse=false, bool check_symmetric=false, bool check_det=false, bool check_psd=false)
Function to solve Ax=b.
Definition: Eigen.cpp:21
Eigen::Matrix4d TransformVector6dToMatrix4d(const Eigen::Vector6d &input)
Definition: Eigen.cpp:76
Generic file read and write utility for python interface.
void swap(cloudViewer::core::SmallVectorImpl< T > &LHS, cloudViewer::core::SmallVectorImpl< T > &RHS)
Implement std::swap in terms of SmallVector swap.
Definition: SmallVector.h:1370