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