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>
36 static const size_t num_reps = mrpt::get_env<int>(
"NUM_REPS", 25);
38 using TPoints = std::vector<mrpt::math::TPoint3D>;
39 using TPlanes = std::vector<mp2p_icp::plane_patch_t>;
43 auto&
rnd = mrpt::random::getRandomGenerator();
48 for (
size_t i = 0; i < nPts; i++)
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);
59 auto&
rnd = mrpt::random::getRandomGenerator();
64 for (
size_t i = 0; i < nPlanes; i++)
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);
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));
75 plA[i].plane = mrpt::math::TPlane(plA[i].centroid, n);
81 std::tuple<mrpt::poses::CPose3D, std::vector<std::size_t>>
84 mrpt::tfest::TMatchingPairList& pointsPairs,
const TPlanes& plA,
85 TPlanes& plB, std::vector<mp2p_icp::matched_plane_t>& planePairs,
87 const double n_err_std ,
const double outliers_ratio)
89 const double outliers_bbox = 50.0;
90 std::vector<std::size_t> gt_outlier_indices;
92 auto&
rnd = mrpt::random::getRandomGenerator();
94 double Dx, Dy, Dz, yaw, pitch, roll;
97 Dx =
rnd.drawUniform(10.0, 20.0);
98 Dy =
rnd.drawUniform(-30.0, -20.0);
99 Dz =
rnd.drawUniform(5.0, 9.0);
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));
107 Dx =
rnd.drawUniform(-1.0, 1.0);
108 Dy =
rnd.drawUniform(-1.0, 1.0);
109 Dz =
rnd.drawUniform(-1.0, 1.0);
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));
116 const auto pose = mrpt::poses::CPose3D(Dx, Dy, Dz, yaw, pitch, roll);
118 const auto pose_rot_only = mrpt::poses::CPose3D(0, 0, 0, yaw, pitch, roll);
121 pB.resize(pA.size());
122 for (std::size_t i = 0; i < pA.size(); ++i)
125 const bool is_outlier = (
rnd.drawUniform(0.0, 1.0) < outliers_ratio);
126 if (is_outlier) gt_outlier_indices.push_back(i);
131 pose.inverseComposePoint(pA[i], pB[i]);
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);
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);
145 mrpt::tfest::TMatchingPair pair;
146 pair.localIdx = pair.globalIdx = i;
151 pointsPairs.push_back(pair);
155 plB.resize(plA.size());
157 pt2plPairs.reserve(plA.size());
159 for (std::size_t i = 0; i < plA.size(); ++i)
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);
167 plB[i].centroid = pose.inverseComposePoint(plA[i].centroid);
172 for (
int k = 0; k < 3; k++)
174 rnd.drawUniform(-outliers_bbox, outliers_bbox);
177 const auto sigma_c = xyz_noise_std;
178 const auto sigma_n = n_err_std;
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);
187 plB[i].plane = plA[i].plane;
190 const mrpt::math::TVector3D ug = plA[i].plane.getNormalVector();
191 mrpt::math::TVector3D ul;
192 pose_rot_only.inverseComposePoint(ug, ul);
194 auto& coefs = plB[i].plane.coefs;
197 if (std::abs(sigma_n) > 1e-9)
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());
205 const double rnd_ang =
rnd.drawGaussian1D(0, sigma_n);
208 mrpt::math::CVectorFixed<double, 3> vv;
209 for (
int k = 0; k < 3; k++) vv[k] = v[k];
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());
216 ul = p.rotateVector(ul);
224 plB[i].plane.unitarize();
227 -(coefs[0] * plB[i].centroid.x +
228 coefs[1] * plB[i].centroid.y +
229 coefs[2] * plB[i].centroid.z);
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();
244 planePairs.push_back(pair);
249 pt2pl.
pt_local = mrpt::math::TPoint3Df(
250 plB[i].centroid.x, plB[i].centroid.y, plB[i].centroid.z);
252 pt2plPairs.push_back(pt2pl);
255 return {pose, gt_outlier_indices};
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)
263 using namespace mrpt::poses::Lie;
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);
274 std::cout <<
"\n== [TEST] " << tstName <<
" =================\n";
276 mrpt::system::CTimeLogger profiler;
277 profiler.setMinLoggingLevel(mrpt::system::LVL_ERROR);
281 mrpt::poses::CPose3D gt_pose;
283 const auto max_allowed_error =
284 std::min(1.0, 0.2 + 10 * xyz_noise_std + 50 * n_err_std);
287 mrpt::math::CMatrixDouble stats(
num_reps, 1 + 3 + 3 + 3);
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;
292 for (
size_t rep = 0; rep <
num_reps; rep++)
301 mrpt::tfest::TMatchingPairList pointPairs;
306 pA, pB, pointPairs, plA, plB, planePairs, pt2plPairs, xyz_noise_std,
307 n_err_std, outliers_ratio);
311 stats(rep, 0) = SO<3>::log(gt_pose.getRotationMatrix()).norm();
316 for (
const auto& p : pt2plPairs)
317 pointPairs.emplace_back(
318 0, 0, 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);
324 gt_pose = this_gt_pose;
334 if (
auto sTh = ::getenv(
"SCALE_OUTLIER_THRESHOLD"); sTh !=
nullptr)
352 profiler.enter(
"olea_match");
358 const auto dt_olea = profiler.leave(
"olea_match");
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();
370 (outliers_ratio < 1e-5 && err_log_n > max_allowed_error))
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);
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);
389 profiler.enter(
"se3_l2");
394 const auto dt_horn = profiler.leave(
"se3_l2");
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();
404 (outliers_ratio < 1e-5 && err_log_n > max_allowed_error))
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);
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;
417 rmse_horn += mrpt::square(err_log_n);
418 rmse_xyz_horn += mrpt::square(err_xyz);
423 profiler.enter(
"optimal_tf_gauss_newton");
443 const auto dt_gn = profiler.leave(
"optimal_tf_gauss_newton");
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();
461 std::cout <<
" -Ground truth : " << gt_pose.asString()
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);
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;
473 rmse_gn += mrpt::square(err_log_n);
474 rmse_xyz_gn += mrpt::square(err_xyz);
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);
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");
490 std::cout <<
" -Ground_truth: " << gt_pose.asString() <<
"\n"
491 <<
" -OLAE output : " << res_olae.
optimalPose.asString() <<
" ("
493 <<
" -Horn output : " << res_horn.
optimalPose.asString() <<
"\n"
494 <<
" -GN output : " << res_gn.
optimalPose.asString()
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);
503 stats.saveToTextFile(
504 mrpt::system::fileNameStripInvalidChars(tstName) +
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");
514 int main([[maybe_unused]]
int argc, [[maybe_unused]]
char** argv)
518 auto&
rnd = mrpt::random::getRandomGenerator();
521 const double nXYZ = 0.001;
522 const double nN = mrpt::DEG2RAD(0.5);
549 for (
int robust = 0; robust <= 1; robust++)
550 for (
double Or = .025; Or < 0.76; Or += 0.025)
552 200 , 0, 0, nXYZ, .0, robust != 0, Or));
555 catch (std::exception& e)
557 std::cerr << mrpt::exception_to_str(e) <<
"\n";