test-mp2p_optimal_tf_algos.cpp
Go to the documentation of this file.
1 /* -------------------------------------------------------------------------
2  * A Modular Optimization framework for Localization and mApping (MOLA)
3  * Copyright (C) 2018-2024 Jose Luis Blanco, University of Almeria
4  * See LICENSE for license information.
5  * ------------------------------------------------------------------------- */
6 
17 #include <mrpt/core/exceptions.h>
18 #include <mrpt/core/get_env.h>
19 #include <mrpt/poses/CPose3D.h>
20 #include <mrpt/poses/CPose3DQuat.h>
21 #include <mrpt/poses/Lie/SO.h>
22 #include <mrpt/random.h>
23 #include <mrpt/system/CTimeLogger.h>
24 #include <mrpt/system/filesystem.h> // fileNameStripInvalidChars()
25 
26 #include <cstdlib>
27 #include <iostream>
28 #include <sstream>
29 
30 // Used to validate OLAE. However, it may make the Gauss-Newton solver, or the
31 // robust kernel with outliers to fail.
32 static bool TEST_LARGE_ROTATIONS = nullptr != ::getenv("TEST_LARGE_ROTATIONS");
33 static bool DO_SAVE_STAT_FILES = nullptr != ::getenv("DO_SAVE_STAT_FILES");
34 static bool DO_PRINT_ALL = nullptr != ::getenv("DO_PRINT_ALL");
35 static bool SKIP_OUTLIERS = nullptr != ::getenv("SKIP_OUTLIERS");
36 static const size_t num_reps = mrpt::get_env<int>("NUM_REPS", 25);
37 
38 using TPoints = std::vector<mrpt::math::TPoint3D>;
39 using TPlanes = std::vector<mp2p_icp::plane_patch_t>;
40 
41 TPoints generate_points(const size_t nPts)
42 {
43  auto& rnd = mrpt::random::getRandomGenerator();
44 
45  TPoints pA;
46  pA.resize(nPts);
47 
48  for (size_t i = 0; i < nPts; i++)
49  {
50  pA[i].x = rnd.drawUniform(0.0, 50.0);
51  pA[i].y = rnd.drawUniform(0.0, 50.0);
52  pA[i].z = rnd.drawUniform(0.0, 50.0);
53  }
54  return pA;
55 }
56 
57 TPlanes generate_planes(const size_t nPlanes)
58 {
59  auto& rnd = mrpt::random::getRandomGenerator();
60 
61  TPlanes plA;
62  plA.resize(nPlanes);
63 
64  for (size_t i = 0; i < nPlanes; i++)
65  {
66  plA[i].centroid.x = rnd.drawUniform(0.0, 50.0);
67  plA[i].centroid.y = rnd.drawUniform(0.0, 50.0);
68  plA[i].centroid.z = rnd.drawUniform(0.0, 50.0);
69 
70  auto n = mrpt::math::TVector3D(
71  rnd.drawUniform(-1.0, 1.0), rnd.drawUniform(-1.0, 1.0), rnd.drawUniform(-1.0, 1.0));
72  n *= 1.0 / n.norm();
73 
74  plA[i].plane = mrpt::math::TPlane(plA[i].centroid, n);
75  }
76  return plA;
77 }
78 
79 // transform features
80 std::tuple<mrpt::poses::CPose3D, std::vector<std::size_t>> transform_points_planes(
81  const TPoints& pA, TPoints& pB, mrpt::tfest::TMatchingPairList& pointsPairs, const TPlanes& plA,
82  TPlanes& plB, std::vector<mp2p_icp::matched_plane_t>& planePairs,
83  mp2p_icp::MatchedPointPlaneList& pt2plPairs, const double xyz_noise_std,
84  const double n_err_std /* normals noise*/, const double outliers_ratio)
85 {
86  const double outliers_bbox = 50.0;
87  std::vector<std::size_t> gt_outlier_indices;
88 
89  auto& rnd = mrpt::random::getRandomGenerator();
90 
91  double Dx, Dy, Dz, yaw, pitch, roll;
93  {
94  Dx = rnd.drawUniform(10.0, 20.0);
95  Dy = rnd.drawUniform(-30.0, -20.0);
96  Dz = rnd.drawUniform(5.0, 9.0);
97 
98  yaw = mrpt::DEG2RAD(rnd.drawUniform(-180.0, 180.0));
99  pitch = mrpt::DEG2RAD(rnd.drawUniform(-89.0, 89.0));
100  roll = mrpt::DEG2RAD(rnd.drawUniform(-89.0, 89.0));
101  }
102  else
103  {
104  Dx = rnd.drawUniform(-1.0, 1.0);
105  Dy = rnd.drawUniform(-1.0, 1.0);
106  Dz = rnd.drawUniform(-1.0, 1.0);
107 
108  yaw = mrpt::DEG2RAD(rnd.drawUniform(-5.0, 5.0));
109  pitch = mrpt::DEG2RAD(rnd.drawUniform(-5.0, 5.0));
110  roll = mrpt::DEG2RAD(rnd.drawUniform(-5.0, 5.0));
111  }
112 
113  const auto pose = mrpt::poses::CPose3D(Dx, Dy, Dz, yaw, pitch, roll);
114  // just the rotation, to transform vectors (vs. R^3 points):
115  const auto pose_rot_only = mrpt::poses::CPose3D(0, 0, 0, yaw, pitch, roll);
116 
117  // Points:
118  pB.resize(pA.size());
119  for (std::size_t i = 0; i < pA.size(); ++i)
120  {
121  // outlier?
122  const bool is_outlier = (rnd.drawUniform(0.0, 1.0) < outliers_ratio);
123  if (is_outlier) gt_outlier_indices.push_back(i);
124 
125  if (!is_outlier)
126  {
127  // Transform + noise:
128  pose.inverseComposePoint(pA[i], pB[i]);
129 
130  pB[i].x += rnd.drawGaussian1D(0, xyz_noise_std);
131  pB[i].y += rnd.drawGaussian1D(0, xyz_noise_std);
132  pB[i].z += rnd.drawGaussian1D(0, xyz_noise_std);
133  }
134  else
135  {
136  pB[i].x = rnd.drawUniform(.0, outliers_bbox);
137  pB[i].y = rnd.drawUniform(.0, outliers_bbox);
138  pB[i].z = rnd.drawUniform(.0, outliers_bbox);
139  }
140 
141  // Add pairing:
142  mrpt::tfest::TMatchingPair pair;
143  pair.localIdx = pair.globalIdx = i;
144 
145  pair.global = pA[i];
146  pair.local = pB[i];
147 
148  pointsPairs.push_back(pair);
149  }
150 
151  // Planes: transform + noise
152  plB.resize(plA.size());
153  pt2plPairs.clear();
154  pt2plPairs.reserve(plA.size());
155 
156  for (std::size_t i = 0; i < plA.size(); ++i)
157  {
158  const bool is_outlier = (rnd.drawUniform(0.0, 1.0) < outliers_ratio);
159  if (is_outlier) gt_outlier_indices.push_back(pA.size() + i);
160 
161  if (!is_outlier)
162  {
163  // Centroid: transform + noise
164  plB[i].centroid = pose.inverseComposePoint(plA[i].centroid);
165  }
166  else
167  {
168  // Outlier
169  for (int k = 0; k < 3; k++)
170  plB[i].centroid[k] = rnd.drawUniform(-outliers_bbox, outliers_bbox);
171  }
172 
173  const auto sigma_c = xyz_noise_std;
174  const auto sigma_n = n_err_std;
175 
176  plB[i].centroid.x += rnd.drawGaussian1D(0, sigma_c);
177  plB[i].centroid.y += rnd.drawGaussian1D(0, sigma_c);
178  plB[i].centroid.z += rnd.drawGaussian1D(0, sigma_c);
179 
180  if (!is_outlier)
181  {
182  // Plane: rotate + noise
183  plB[i].plane = plA[i].plane;
184 
185  {
186  const mrpt::math::TVector3D ug = plA[i].plane.getNormalVector();
187  mrpt::math::TVector3D ul;
188  pose_rot_only.inverseComposePoint(ug, ul);
189 
190  auto& coefs = plB[i].plane.coefs;
191 
192  // Generate a random SO(3) rotation: angle \sim Gaussian(0,s_n)
193  if (std::abs(sigma_n) > 1e-9)
194  {
195  // unit vector at an arbitrary direction:
196  auto v = mrpt::math::TVector3D(
197  rnd.drawUniform(-1.0, 1.0), rnd.drawUniform(-1.0, 1.0),
198  rnd.drawUniform(-1.0, 1.0));
199  v *= (1.0 / v.norm());
200 
201  const double rnd_ang = rnd.drawGaussian1D(0, sigma_n);
202  v *= rnd_ang;
203 
204  mrpt::math::CVectorFixed<double, 3> vv;
205  for (int k = 0; k < 3; k++) vv[k] = v[k];
206 
207  const auto R33 = mrpt::poses::Lie::SO<3>::exp(vv);
208  const auto p =
209  mrpt::poses::CPose3D(R33, mrpt::math::CVectorFixed<double, 3>::Zero());
210 
211  // Noisy plane normal:
212  ul = p.rotateVector(ul);
213  }
214 
215  // Ax+By+Cz+D=0
216  coefs[0] = ul.x;
217  coefs[1] = ul.y;
218  coefs[2] = ul.z;
219  coefs[3] = 0; // temporary.
220  plB[i].plane.unitarize();
221 
222  coefs[3] =
223  -(coefs[0] * plB[i].centroid.x + coefs[1] * plB[i].centroid.y +
224  coefs[2] * plB[i].centroid.z);
225  }
226  }
227  else
228  {
229  // Outlier:
230  for (int k = 0; k < 4; k++) plB[i].plane.coefs[k] = rnd.drawUniform(-1.0, 1.0);
231  plB[i].plane.unitarize();
232  }
233 
234  // Add plane-plane pairing:
236  pair.p_global = plA[i];
237  pair.p_local = plB[i];
238  planePairs.push_back(pair);
239 
240  // Add point-plane pairing:
242  pt2pl.pl_global = plA[i];
243  pt2pl.pt_local =
244  mrpt::math::TPoint3Df(plB[i].centroid.x, plB[i].centroid.y, plB[i].centroid.z);
245 
246  pt2plPairs.push_back(pt2pl);
247  }
248 
249  return {pose, gt_outlier_indices};
250 }
251 
253  const size_t numPts, const size_t numLines, const size_t numPlanes,
254  const double xyz_noise_std = .0, const double n_err_std = .0, bool use_robust = false,
255  const double outliers_ratio = .0)
256 {
257  using namespace mrpt::poses::Lie;
258 
259  MRPT_START
260 
261  const std::string tstName = mrpt::format(
262  "test_icp_algos_nPt=%06u_nLin=%06u_nPl=%06u_xyzStd=%.04f_nStd=%."
263  "04f_outliers=%06.03f_robust=%i",
264  static_cast<unsigned int>(numPts), static_cast<unsigned int>(numLines),
265  static_cast<unsigned int>(numPlanes), xyz_noise_std, n_err_std, outliers_ratio,
266  use_robust ? 1 : 0);
267 
268  std::cout << "\n== [TEST] " << tstName << " =================\n";
269 
270  mrpt::system::CTimeLogger profiler;
271  profiler.setMinLoggingLevel(mrpt::system::LVL_ERROR); // to make it quiet
272 
273  // Repeat the test many times, with different random values:
274  mp2p_icp::OptimalTF_Result res_olae, res_horn, res_gn;
275  mrpt::poses::CPose3D gt_pose;
276 
277  const auto max_allowed_error = std::min(1.0, 0.2 + 10 * xyz_noise_std + 50 * n_err_std);
278 
279  // Collect stats: columns are (see write TXT to file code at the bottom)
280  mrpt::math::CMatrixDouble stats(num_reps, 1 + 3 + 3 + 3);
281 
282  double rmse_olea = 0, rmse_horn = 0, rmse_gn = 0;
283  double rmse_xyz_olea = 0, rmse_xyz_horn = 0, rmse_xyz_gn = 0;
284 
285  for (size_t rep = 0; rep < num_reps; rep++)
286  {
287  // The input points & planes
288  const TPoints pA = generate_points(numPts);
289  const TPlanes plA = generate_planes(numPlanes);
290 
291  TPoints pB;
292  TPlanes plB;
293 
294  mrpt::tfest::TMatchingPairList pointPairs;
295  mp2p_icp::MatchedPlaneList planePairs;
297 
298  const auto [this_gt_pose, this_outliers] = transform_points_planes(
299  pA, pB, pointPairs, plA, plB, planePairs, pt2plPairs, xyz_noise_std, n_err_std,
300  outliers_ratio);
301 
302  (void)this_outliers; // unused var
303 
304  stats(rep, 0) = SO<3>::log(gt_pose.getRotationMatrix()).norm();
305 
306 #if 0
307  // Also add the plane-centroid-to-plane-centroid as point-to-point
308  // constraints:
309  for (const auto& p : pt2plPairs)
310  pointPairs.emplace_back(
311  0, 0, /*indices not used here*/ p.pl_this.centroid.x,
312  p.pl_this.centroid.y, p.pl_this.centroid.z, p.pt_other.x,
313  p.pt_other.y, p.pt_other.z);
314 #endif
315 
316  // to show the result of the last iteration at end
317  gt_pose = this_gt_pose;
318 
320 
322  in.paired_pt2pt = pointPairs;
323  in.paired_pl2pl = planePairs;
324 
325  wp.use_scale_outlier_detector = false;
326 #if 0
327  if (auto sTh = ::getenv("SCALE_OUTLIER_THRESHOLD"); sTh != nullptr)
328  wp.scale_outlier_threshold = ::atof(sTh);
329 #endif
330 
331  // Only for tests with outliers, and if we are using small rotations,
332  // use the robust kernel, using the identity SE(3) transform as
333  // gross initial guess for the pose:
334  // if (!TEST_LARGE_ROTATIONS && outliers_ratio > 0)
335  if (use_robust && !TEST_LARGE_ROTATIONS)
336  {
338  wp.robust_kernel_param = 1.0;
339  wp.currentEstimateForRobust = gt_pose;
340  // mrpt::poses::CPose3D::Identity();
341  }
342 
343  // ======== TEST: olae_match ========
344  {
345  profiler.enter("olea_match");
346 
347  bool ok = mp2p_icp::optimal_tf_olae(in, wp, res_olae);
348  ASSERT_(ok);
349 
350  // const double dt_last =
351  const auto dt_olea = profiler.leave("olea_match");
352 
353  // Collect stats:
354 
355  // Measure errors in SE(3) if we have many points, in SO(3)
356  // otherwise:
357  const auto pos_error = gt_pose - res_olae.optimalPose;
358  const auto err_log_n = SO<3>::log(pos_error.getRotationMatrix()).norm();
359  const auto err_xyz = pos_error.norm();
360 
361  if (DO_PRINT_ALL || (outliers_ratio < 1e-5 && err_log_n > max_allowed_error))
362  {
363  std::cout << " -Ground_truth : " << gt_pose.asString() << "\n"
364  << " -OLAE_output : " << res_olae.optimalPose.asString()
365  << "\n -GT_rot:\n"
366  << gt_pose.getRotationMatrix() << "\n -OLAE_rot:\n"
367  << res_olae.optimalPose.getRotationMatrix() << "\n";
368  ASSERT_LT_(err_log_n, max_allowed_error);
369  }
370 
371  stats(rep, 1 + 3 * 0 + 0) = err_log_n;
372  stats(rep, 1 + 3 * 1 + 0) = err_xyz;
373  stats(rep, 1 + 3 * 2 + 0) = dt_olea;
374  rmse_olea += mrpt::square(err_log_n);
375  rmse_xyz_olea += mrpt::square(err_xyz);
376  }
377 
378  // ======== TEST: Classic Horn ========
379  {
380  profiler.enter("se3_l2");
381 
382  bool ok = mp2p_icp::optimal_tf_horn(in, wp, res_horn);
383  ASSERT_(ok);
384 
385  const auto dt_horn = profiler.leave("se3_l2");
386 
387  const auto pos_error = gt_pose - res_horn.optimalPose;
388  const auto err_log_n = SO<3>::log(pos_error.getRotationMatrix()).norm();
389  const auto err_xyz = pos_error.norm();
390 
391  // Don't make the tests fail if we have outliers, since it IS
392  // expected that, sometimes, we don't get to the optimum
393  if (DO_PRINT_ALL || (outliers_ratio < 1e-5 && err_log_n > max_allowed_error))
394  {
395  std::cout << " -Ground_truth : " << gt_pose.asString() << "\n"
396  << " -Horn_output : " << res_horn.optimalPose.asString()
397  << "\n -GT_rot:\n"
398  << gt_pose.getRotationMatrix() << "\n";
399  ASSERT_LT_(err_log_n, max_allowed_error);
400  }
401 
402  stats(rep, 1 + 3 * 0 + 1) = err_log_n;
403  stats(rep, 1 + 3 * 1 + 1) = err_xyz;
404  stats(rep, 1 + 3 * 2 + 1) = dt_horn;
405 
406  rmse_horn += mrpt::square(err_log_n);
407  rmse_xyz_horn += mrpt::square(err_xyz);
408  }
409 
410  // ======== TEST: GaussNewton method ========
411  {
412  profiler.enter("optimal_tf_gauss_newton");
413 
415  gnParams.verbose = false;
416  // Linearization point: Identity
417  gnParams.linearizationPoint = mrpt::poses::CPose3D();
418 
419  if (use_robust)
420  {
422  gnParams.kernelParam = 1;
423  }
424 
425  // NOTE: this is an "unfair" comparison, since we only run ONE
426  // iteration of the GN while the other methods are one-shot
427  // solutions. But GN is good enough even so for small rotations to
428  // solve it in just one iteration.
429  bool ok = mp2p_icp::optimal_tf_gauss_newton(in, res_gn, gnParams);
430  ASSERT_(ok);
431 
432  const auto dt_gn = profiler.leave("optimal_tf_gauss_newton");
433 
434  const auto pos_error = gt_pose - res_gn.optimalPose;
435  const auto err_log_n = SO<3>::log(pos_error.getRotationMatrix()).norm();
436  const auto err_xyz = pos_error.norm();
437 
438  // Don't make the tests fail if we have outliers, since it IS
439  // expected that, sometimes, we don't get to the optimum
440  // Also, disable gauss-newton checks for large rotations, as it
441  // fails, and that's expected since it's a local algorithm.
442  if (0)
443  /*
444  !TEST_LARGE_ROTATIONS &&
445  //(DO_PRINT_ALL ||
446  (outliers_ratio < 1e-5 && err_log_n > max_allowed_error)))
447  */
448  {
449  std::cout << " -Ground truth : " << gt_pose.asString() << "\n"
450  << " -GaussNewton output : " << res_gn.optimalPose.asString()
451  << "\n -GT_rot:\n"
452  << gt_pose.getRotationMatrix() << "\n";
453  ASSERT_LT_(err_log_n, max_allowed_error);
454  }
455 
456  stats(rep, 1 + 3 * 0 + 2) = err_log_n;
457  stats(rep, 1 + 3 * 1 + 2) = err_xyz;
458  stats(rep, 1 + 3 * 2 + 2) = dt_gn;
459 
460  rmse_gn += mrpt::square(err_log_n);
461  rmse_xyz_gn += mrpt::square(err_xyz);
462  }
463  } // for each repetition
464 
465  // RMSE:
466  rmse_olea = std::sqrt(rmse_olea / num_reps);
467  rmse_xyz_olea = std::sqrt(rmse_xyz_olea / num_reps);
468  rmse_horn = std::sqrt(rmse_horn / num_reps);
469  rmse_xyz_horn = std::sqrt(rmse_xyz_horn / num_reps);
470  rmse_gn = std::sqrt(rmse_gn / num_reps);
471  rmse_xyz_gn = std::sqrt(rmse_xyz_gn / num_reps);
472 
473  const double dt_olea = profiler.getMeanTime("olea_match");
474  const double dt_horn = profiler.getMeanTime("se3_l2");
475  const double dt_gn = profiler.getMeanTime("optimal_tf_gauss_newton");
476 
477  std::cout << " -Ground_truth: " << gt_pose.asString() << "\n"
478  << " -OLAE output : " << res_olae.optimalPose.asString() << " ("
479  << res_olae.outliers.size() << " outliers detected)\n"
480  << " -Horn output : " << res_horn.optimalPose.asString() << "\n"
481  << " -GN output : " << res_gn.optimalPose.asString()
482  << "\n"
483  // clang-format off
484  << " -OLAE : " << mrpt::format("SO3 rmse=%e XYZ rmse=%e time=%7.03f us\n",rmse_olea, rmse_xyz_olea, dt_olea * 1e6)
485  << " -Horn : " << mrpt::format("SO3 rmse=%e XYZ rmse=%e time=%7.03f us\n",rmse_horn, rmse_xyz_horn, dt_horn * 1e6)
486  << " -Gauss-Newton: " << mrpt::format("SO3 rmse=%e XYZ rmse=%e time=%7.03f us\n",rmse_gn, rmse_xyz_gn, dt_gn * 1e6);
487  // clang-format on
488 
489  if (DO_SAVE_STAT_FILES)
490  stats.saveToTextFile(
491  mrpt::system::fileNameStripInvalidChars(tstName) + std::string(".txt"),
492  mrpt::math::MATRIX_FORMAT_ENG, true,
493  "% Columns: execution time x 3, norm(SO3_error) x3, "
494  "norm(XYZ_error) x3 (OLAE, Horn, GaussNewton)\n\n");
495 
496  return true; // all ok.
497  MRPT_END
498 }
499 
500 int main([[maybe_unused]] int argc, [[maybe_unused]] char** argv)
501 {
502  try
503  {
504  auto& rnd = mrpt::random::getRandomGenerator();
505  rnd.randomize(1234); // for reproducible tests
506 
507  const double nXYZ = 0.001; // [meters] std. noise of XYZ points
508  const double nN = mrpt::DEG2RAD(0.5); // normals noise
509 
510  // arguments: nPts, nLines, nPlanes
511  // Points only. Noiseless:
512  ASSERT_(test_icp_algos(3 /*pt*/, 0 /*li*/, 0 /*pl*/));
513  ASSERT_(test_icp_algos(4 /*pt*/, 0 /*li*/, 0 /*pl*/));
514  ASSERT_(test_icp_algos(10 /*pt*/, 0 /*li*/, 0 /*pl*/));
515  ASSERT_(test_icp_algos(100 /*pt*/, 0 /*li*/, 0 /*pl*/));
516  ASSERT_(test_icp_algos(1000 /*pt*/, 0 /*li*/, 0 /*pl*/));
517 
518  // Points only. Noisy:
519  ASSERT_(test_icp_algos(100 /*pt*/, 0 /*li*/, 0 /*pl*/, nXYZ));
520  ASSERT_(test_icp_algos(1000 /*pt*/, 0 /*li*/, 0 /*pl*/, nXYZ));
521 
522  // Planes + 1 pt. Noiseless:
523  ASSERT_(test_icp_algos(2 /*pt*/, 0 /*li*/, 1 /*pl*/));
524  ASSERT_(test_icp_algos(2 /*pt*/, 0 /*li*/, 10 /*pl*/));
525  ASSERT_(test_icp_algos(2 /*pt*/, 0 /*li*/, 100 /*pl*/));
526 
527  // Points and planes, noisy.
528  ASSERT_(test_icp_algos(2 /*pt*/, 0 /*li*/, 1 /*pl*/, nXYZ, nN));
529  ASSERT_(test_icp_algos(10 /*pt*/, 0 /*li*/, 10 /*pl*/, nXYZ, nN));
530  ASSERT_(test_icp_algos(100 /*pt*/, 0 /*li*/, 100 /*pl*/, nXYZ, nN));
531 
532  if (!SKIP_OUTLIERS)
533  {
534  // Points only. Noisy w. outliers:
535  for (int robust = 0; robust <= 1; robust++)
536  for (double Or = .025; Or < 0.76; Or += 0.025)
537  ASSERT_(test_icp_algos(200 /*pt*/, 0, 0, nXYZ, .0, robust != 0, Or));
538  }
539  }
540  catch (std::exception& e)
541  {
542  std::cerr << mrpt::exception_to_str(e) << "\n";
543  return 1;
544  }
545 }
mp2p_icp::OptimalTF_GN_Parameters
Definition: optimal_tf_gauss_newton.h:24
mp2p_icp::optimal_tf_gauss_newton
bool optimal_tf_gauss_newton(const Pairings &in, OptimalTF_Result &result, const OptimalTF_GN_Parameters &gnParams=OptimalTF_GN_Parameters())
Definition: optimal_tf_gauss_newton.cpp:28
TPlanes
std::vector< mp2p_icp::plane_patch_t > TPlanes
Definition: test-mp2p_optimal_tf_algos.cpp:39
mp2p_icp::OptimalTF_Result::optimalPose
mrpt::poses::CPose3D optimalPose
Definition: OptimalTF_Result.h:26
mp2p_icp::OptimalTF_GN_Parameters::kernelParam
double kernelParam
Definition: optimal_tf_gauss_newton.h:50
DO_PRINT_ALL
static bool DO_PRINT_ALL
Definition: test-mp2p_optimal_tf_algos.cpp:34
mp2p_icp::matched_plane_t::p_global
plane_patch_t p_global
Definition: Pairings.h:31
mp2p_icp::optimal_tf_horn
bool optimal_tf_horn(const mp2p_icp::Pairings &in, const WeightParameters &wp, OptimalTF_Result &result)
Definition: optimal_tf_horn.cpp:193
mp2p_icp::point_plane_pair_t
Definition: point_plane_pair_t.h:26
mp2p_icp::point_plane_pair_t::pl_global
plane_patch_t pl_global
Definition: point_plane_pair_t.h:28
num_reps
static const size_t num_reps
Definition: test-mp2p_optimal_tf_algos.cpp:36
mp2p_icp::MatchedPlaneList
std::vector< matched_plane_t > MatchedPlaneList
Definition: Pairings.h:41
mp2p_icp::Pairings
Definition: Pairings.h:76
mp2p_icp::WeightParameters::use_scale_outlier_detector
bool use_scale_outlier_detector
Definition: WeightParameters.h:35
mp2p_icp::MatchedPointPlaneList
std::vector< point_plane_pair_t > MatchedPointPlaneList
Definition: point_plane_pair_t.h:39
mp2p_icp::matched_plane_t::p_local
plane_patch_t p_local
Definition: Pairings.h:31
mp2p_icp::OptimalTF_GN_Parameters::verbose
bool verbose
Definition: optimal_tf_gauss_newton.h:52
generate_points
TPoints generate_points(const size_t nPts)
Definition: test-mp2p_optimal_tf_algos.cpp:41
mp2p_icp::OptimalTF_GN_Parameters::kernel
RobustKernel kernel
Definition: optimal_tf_gauss_newton.h:49
optimal_tf_olae.h
OLAE algorithm to find the SE(3) optimal transformation.
mp2p_icp::OptimalTF_Result
Definition: OptimalTF_Result.h:24
ok
ROSCPP_DECL bool ok()
testing::internal::string
::std::string string
Definition: gtest.h:1979
mp2p_icp::OptimalTF_Result::outliers
OutlierIndices outliers
Definition: OptimalTF_Result.h:30
optimal_tf_gauss_newton.h
Simple non-linear optimizer to find the SE(3) optimal transformation.
TEST_LARGE_ROTATIONS
static bool TEST_LARGE_ROTATIONS
Definition: test-mp2p_optimal_tf_algos.cpp:32
rnd
auto & rnd
Definition: test-mp2p_error_terms_jacobians.cpp:28
mp2p_icp::WeightParameters::robust_kernel_param
double robust_kernel_param
Definition: WeightParameters.h:56
transform_points_planes
std::tuple< mrpt::poses::CPose3D, std::vector< std::size_t > > transform_points_planes(const TPoints &pA, TPoints &pB, mrpt::tfest::TMatchingPairList &pointsPairs, const TPlanes &plA, TPlanes &plB, std::vector< mp2p_icp::matched_plane_t > &planePairs, mp2p_icp::MatchedPointPlaneList &pt2plPairs, const double xyz_noise_std, const double n_err_std, const double outliers_ratio)
Definition: test-mp2p_optimal_tf_algos.cpp:80
mp2p_icp::RobustKernel::GemanMcClure
@ GemanMcClure
Generalized GemanMcClure kernel (Zhang97ivc, Agarwal15phd).
mp2p_icp::OutlierIndices::size
std::size_t size() const
Definition: Pairings.h:182
main
int main([[maybe_unused]] int argc, [[maybe_unused]] char **argv)
Definition: test-mp2p_optimal_tf_algos.cpp:500
TPoints
std::vector< mrpt::math::TPoint3D > TPoints
Definition: test-mp2p_optimal_tf_algos.cpp:38
mp2p_icp::optimal_tf_olae
bool optimal_tf_olae(const Pairings &in, const WeightParameters &wp, OptimalTF_Result &result)
Definition: optimal_tf_olae.cpp:233
mp2p_icp::OptimalTF_GN_Parameters::linearizationPoint
std::optional< mrpt::poses::CPose3D > linearizationPoint
Definition: optimal_tf_gauss_newton.h:29
mp2p_icp::WeightParameters::currentEstimateForRobust
std::optional< mrpt::poses::CPose3D > currentEstimateForRobust
Definition: WeightParameters.h:54
mp2p_icp::Pairings::paired_pl2pl
MatchedPlaneList paired_pl2pl
Definition: Pairings.h:90
test_icp_algos
bool test_icp_algos(const size_t numPts, const size_t numLines, const size_t numPlanes, const double xyz_noise_std=.0, const double n_err_std=.0, bool use_robust=false, const double outliers_ratio=.0)
Definition: test-mp2p_optimal_tf_algos.cpp:252
DO_SAVE_STAT_FILES
static bool DO_SAVE_STAT_FILES
Definition: test-mp2p_optimal_tf_algos.cpp:33
mp2p_icp::WeightParameters::scale_outlier_threshold
double scale_outlier_threshold
Definition: WeightParameters.h:43
mp2p_icp::point_plane_pair_t::pt_local
mrpt::math::TPoint3Df pt_local
Definition: point_plane_pair_t.h:29
generate_planes
TPlanes generate_planes(const size_t nPlanes)
Definition: test-mp2p_optimal_tf_algos.cpp:57
mp2p_icp::matched_plane_t
Definition: Pairings.h:29
optimal_tf_horn.h
Classic Horn's solution for optimal SE(3) transformation.
mp2p_icp::WeightParameters
Definition: WeightParameters.h:26
mp2p_icp::Pairings::paired_pt2pt
mrpt::tfest::TMatchingPairList paired_pt2pt
Definition: Pairings.h:86
SKIP_OUTLIERS
static bool SKIP_OUTLIERS
Definition: test-mp2p_optimal_tf_algos.cpp:35
mp2p_icp::WeightParameters::robust_kernel
RobustKernel robust_kernel
Definition: WeightParameters.h:50


mp2p_icp
Author(s):
autogenerated on Mon May 26 2025 02:45:50