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),
rnd.drawUniform(-1.0, 1.0));
74 plA[i].plane = mrpt::math::TPlane(plA[i].centroid, n);
82 TPlanes& plB, std::vector<mp2p_icp::matched_plane_t>& planePairs,
84 const double n_err_std ,
const double outliers_ratio)
86 const double outliers_bbox = 50.0;
87 std::vector<std::size_t> gt_outlier_indices;
89 auto&
rnd = mrpt::random::getRandomGenerator();
91 double Dx, Dy, Dz, yaw, pitch, roll;
94 Dx =
rnd.drawUniform(10.0, 20.0);
95 Dy =
rnd.drawUniform(-30.0, -20.0);
96 Dz =
rnd.drawUniform(5.0, 9.0);
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));
104 Dx =
rnd.drawUniform(-1.0, 1.0);
105 Dy =
rnd.drawUniform(-1.0, 1.0);
106 Dz =
rnd.drawUniform(-1.0, 1.0);
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));
113 const auto pose = mrpt::poses::CPose3D(Dx, Dy, Dz, yaw, pitch, roll);
115 const auto pose_rot_only = mrpt::poses::CPose3D(0, 0, 0, yaw, pitch, roll);
118 pB.resize(pA.size());
119 for (std::size_t i = 0; i < pA.size(); ++i)
122 const bool is_outlier = (
rnd.drawUniform(0.0, 1.0) < outliers_ratio);
123 if (is_outlier) gt_outlier_indices.push_back(i);
128 pose.inverseComposePoint(pA[i], pB[i]);
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);
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);
142 mrpt::tfest::TMatchingPair pair;
143 pair.localIdx = pair.globalIdx = i;
148 pointsPairs.push_back(pair);
152 plB.resize(plA.size());
154 pt2plPairs.reserve(plA.size());
156 for (std::size_t i = 0; i < plA.size(); ++i)
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);
164 plB[i].centroid = pose.inverseComposePoint(plA[i].centroid);
169 for (
int k = 0; k < 3; k++)
170 plB[i].centroid[k] =
rnd.drawUniform(-outliers_bbox, outliers_bbox);
173 const auto sigma_c = xyz_noise_std;
174 const auto sigma_n = n_err_std;
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);
183 plB[i].plane = plA[i].plane;
186 const mrpt::math::TVector3D ug = plA[i].plane.getNormalVector();
187 mrpt::math::TVector3D ul;
188 pose_rot_only.inverseComposePoint(ug, ul);
190 auto& coefs = plB[i].plane.coefs;
193 if (std::abs(sigma_n) > 1e-9)
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());
201 const double rnd_ang =
rnd.drawGaussian1D(0, sigma_n);
204 mrpt::math::CVectorFixed<double, 3> vv;
205 for (
int k = 0; k < 3; k++) vv[k] = v[k];
207 const auto R33 = mrpt::poses::Lie::SO<3>::exp(vv);
209 mrpt::poses::CPose3D(R33, mrpt::math::CVectorFixed<double, 3>::Zero());
212 ul = p.rotateVector(ul);
220 plB[i].plane.unitarize();
223 -(coefs[0] * plB[i].centroid.x + coefs[1] * plB[i].centroid.y +
224 coefs[2] * plB[i].centroid.z);
230 for (
int k = 0; k < 4; k++) plB[i].plane.coefs[k] =
rnd.drawUniform(-1.0, 1.0);
231 plB[i].plane.unitarize();
238 planePairs.push_back(pair);
244 mrpt::math::TPoint3Df(plB[i].centroid.x, plB[i].centroid.y, plB[i].centroid.z);
246 pt2plPairs.push_back(pt2pl);
249 return {pose, gt_outlier_indices};
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)
257 using namespace mrpt::poses::Lie;
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,
268 std::cout <<
"\n== [TEST] " << tstName <<
" =================\n";
270 mrpt::system::CTimeLogger profiler;
271 profiler.setMinLoggingLevel(mrpt::system::LVL_ERROR);
275 mrpt::poses::CPose3D gt_pose;
277 const auto max_allowed_error = std::min(1.0, 0.2 + 10 * xyz_noise_std + 50 * n_err_std);
280 mrpt::math::CMatrixDouble stats(
num_reps, 1 + 3 + 3 + 3);
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;
285 for (
size_t rep = 0; rep <
num_reps; rep++)
294 mrpt::tfest::TMatchingPairList pointPairs;
299 pA, pB, pointPairs, plA, plB, planePairs, pt2plPairs, xyz_noise_std, n_err_std,
304 stats(rep, 0) = SO<3>::log(gt_pose.getRotationMatrix()).norm();
309 for (
const auto& p : pt2plPairs)
310 pointPairs.emplace_back(
311 0, 0, 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);
317 gt_pose = this_gt_pose;
327 if (
auto sTh = ::getenv(
"SCALE_OUTLIER_THRESHOLD"); sTh !=
nullptr)
345 profiler.enter(
"olea_match");
351 const auto dt_olea = profiler.leave(
"olea_match");
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();
361 if (
DO_PRINT_ALL || (outliers_ratio < 1e-5 && err_log_n > max_allowed_error))
363 std::cout <<
" -Ground_truth : " << gt_pose.asString() <<
"\n"
364 <<
" -OLAE_output : " << res_olae.
optimalPose.asString()
366 << gt_pose.getRotationMatrix() <<
"\n -OLAE_rot:\n"
367 << res_olae.
optimalPose.getRotationMatrix() <<
"\n";
368 ASSERT_LT_(err_log_n, max_allowed_error);
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);
380 profiler.enter(
"se3_l2");
385 const auto dt_horn = profiler.leave(
"se3_l2");
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();
393 if (
DO_PRINT_ALL || (outliers_ratio < 1e-5 && err_log_n > max_allowed_error))
395 std::cout <<
" -Ground_truth : " << gt_pose.asString() <<
"\n"
396 <<
" -Horn_output : " << res_horn.
optimalPose.asString()
398 << gt_pose.getRotationMatrix() <<
"\n";
399 ASSERT_LT_(err_log_n, max_allowed_error);
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;
406 rmse_horn += mrpt::square(err_log_n);
407 rmse_xyz_horn += mrpt::square(err_xyz);
412 profiler.enter(
"optimal_tf_gauss_newton");
432 const auto dt_gn = profiler.leave(
"optimal_tf_gauss_newton");
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();
449 std::cout <<
" -Ground truth : " << gt_pose.asString() <<
"\n"
450 <<
" -GaussNewton output : " << res_gn.
optimalPose.asString()
452 << gt_pose.getRotationMatrix() <<
"\n";
453 ASSERT_LT_(err_log_n, max_allowed_error);
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;
460 rmse_gn += mrpt::square(err_log_n);
461 rmse_xyz_gn += mrpt::square(err_xyz);
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);
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");
477 std::cout <<
" -Ground_truth: " << gt_pose.asString() <<
"\n"
478 <<
" -OLAE output : " << res_olae.
optimalPose.asString() <<
" ("
480 <<
" -Horn output : " << res_horn.
optimalPose.asString() <<
"\n"
481 <<
" -GN output : " << res_gn.
optimalPose.asString()
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);
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");
500 int main([[maybe_unused]]
int argc, [[maybe_unused]]
char** argv)
504 auto&
rnd = mrpt::random::getRandomGenerator();
507 const double nXYZ = 0.001;
508 const double nN = mrpt::DEG2RAD(0.5);
535 for (
int robust = 0; robust <= 1; robust++)
536 for (
double Or = .025; Or < 0.76; Or += 0.025)
540 catch (std::exception& e)
542 std::cerr << mrpt::exception_to_str(e) <<
"\n";