From f85e43c684ac9651344a922e20aed1f672d0a478 Mon Sep 17 00:00:00 2001 From: tizianoGuadagnino Date: Tue, 19 Sep 2023 15:26:41 +0200 Subject: [PATCH 1/2] BuildLinearSystem function, allow computing the covariance at convergence from the cpp API --- cpp/kiss_icp/core/Registration.cpp | 36 ++++++++++++++++-------------- cpp/kiss_icp/core/Registration.hpp | 10 +++++++++ 2 files changed, 29 insertions(+), 17 deletions(-) diff --git a/cpp/kiss_icp/core/Registration.cpp b/cpp/kiss_icp/core/Registration.cpp index bcce75af..ed6c3b05 100644 --- a/cpp/kiss_icp/core/Registration.cpp +++ b/cpp/kiss_icp/core/Registration.cpp @@ -32,9 +32,7 @@ #include namespace Eigen { -using Matrix6d = Eigen::Matrix; using Matrix3_6d = Eigen::Matrix; -using Vector6d = Eigen::Matrix; } // namespace Eigen namespace { @@ -62,9 +60,17 @@ void TransformPoints(const Sophus::SE3d &T, std::vector &points [&](const auto &point) { return T * point; }); } -Sophus::SE3d AlignClouds(const std::vector &source, - const std::vector &target, - double th) { +constexpr int MAX_NUM_ITERATIONS_ = 500; +constexpr double ESTIMATION_THRESHOLD_ = 0.0001; + +} // namespace + +namespace kiss_icp { + +std::tuple BuildLinearSystem( + const std::vector &source, + const std::vector &target, + double kernel) { auto compute_jacobian_and_residual = [&](auto i) { const Eigen::Vector3d residual = source[i] - target[i]; Eigen::Matrix3_6d J_r; @@ -80,7 +86,9 @@ Sophus::SE3d AlignClouds(const std::vector &source, ResultTuple(), // 1st Lambda: Parallel computation [&](const tbb::blocked_range &r, ResultTuple J) -> ResultTuple { - auto Weight = [&](double residual2) { return square(th) / square(th + residual2); }; + auto Weight = [&](double residual2) { + return square(kernel) / square(kernel + residual2); + }; auto &[JTJ_private, JTr_private] = J; for (auto i = r.begin(); i < r.end(); ++i) { const auto &[J_r, residual] = compute_jacobian_and_residual(i); @@ -93,17 +101,9 @@ Sophus::SE3d AlignClouds(const std::vector &source, // 2nd Lambda: Parallel reduction of the private Jacboians [&](ResultTuple a, const ResultTuple &b) -> ResultTuple { return a + b; }); - const Eigen::Vector6d x = JTJ.ldlt().solve(-JTr); - return Sophus::SE3d::exp(x); + return std::make_tuple(JTJ, JTr); } -constexpr int MAX_NUM_ITERATIONS_ = 500; -constexpr double ESTIMATION_THRESHOLD_ = 0.0001; - -} // namespace - -namespace kiss_icp { - Sophus::SE3d RegisterFrame(const std::vector &frame, const VoxelHashMap &voxel_map, const Sophus::SE3d &initial_guess, @@ -121,13 +121,15 @@ Sophus::SE3d RegisterFrame(const std::vector &frame, // Equation (10) const auto &[src, tgt] = voxel_map.GetCorrespondences(source, max_correspondence_distance); // Equation (11) - auto estimation = AlignClouds(src, tgt, kernel); + auto &[JTJ, JTr] = BuildLinearSystem(src, tgt, kernel); + const Eigen::Vector6d dx = JTJ.ldlt().solve(-JTr); + const Sophus::SE3d estimation = Sophus::SE3d::exp(dx); // Equation (12) TransformPoints(estimation, source); // Update iterations T_icp = estimation * T_icp; // Termination criteria - if (estimation.log().norm() < ESTIMATION_THRESHOLD_) break; + if (dx.norm() < ESTIMATION_THRESHOLD_) break; } // Spit the final transformation return T_icp * initial_guess; diff --git a/cpp/kiss_icp/core/Registration.hpp b/cpp/kiss_icp/core/Registration.hpp index eb82d37b..05d1dc99 100644 --- a/cpp/kiss_icp/core/Registration.hpp +++ b/cpp/kiss_icp/core/Registration.hpp @@ -28,8 +28,18 @@ #include "VoxelHashMap.hpp" +namespace Eigen { +using Matrix6d = Eigen::Matrix; +using Vector6d = Eigen::Matrix; +} // namespace Eigen + namespace kiss_icp { +std::tuple BuildLinearSystem( + const std::vector &source, + const std::vector &target, + double kernel); + Sophus::SE3d RegisterFrame(const std::vector &frame, const VoxelHashMap &voxel_map, const Sophus::SE3d &initial_guess, From 3bf597b145cd0b45d9636faaab9bed15bc8daaec Mon Sep 17 00:00:00 2001 From: tizianoGuadagnino Date: Fri, 13 Oct 2023 11:21:43 +0200 Subject: [PATCH 2/2] Add const ;) --- cpp/kiss_icp/core/Registration.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cpp/kiss_icp/core/Registration.cpp b/cpp/kiss_icp/core/Registration.cpp index ed6c3b05..c3e0d49c 100644 --- a/cpp/kiss_icp/core/Registration.cpp +++ b/cpp/kiss_icp/core/Registration.cpp @@ -121,7 +121,7 @@ Sophus::SE3d RegisterFrame(const std::vector &frame, // Equation (10) const auto &[src, tgt] = voxel_map.GetCorrespondences(source, max_correspondence_distance); // Equation (11) - auto &[JTJ, JTr] = BuildLinearSystem(src, tgt, kernel); + const auto &[JTJ, JTr] = BuildLinearSystem(src, tgt, kernel); const Eigen::Vector6d dx = JTJ.ldlt().solve(-JTr); const Sophus::SE3d estimation = Sophus::SE3d::exp(dx); // Equation (12)