/////////////////////////////////////////////////////////////////////////////// /// "Sparse Iterative Closest Point" /// by Sofien Bouaziz, Andrea Tagliasacchi, Mark Pauly /// Copyright (C) 2013 LGG, EPFL /////////////////////////////////////////////////////////////////////////////// /// 1) This file contains different implementations of the ICP algorithm. /// 2) This code requires EIGEN and NANOFLANN. /// 3) If OPENMP is activated some part of the code will be parallelized. /// 4) This code is for now designed for 3D registration /// 5) Two main input types are Eigen::Matrix3Xd or Eigen::Map /////////////////////////////////////////////////////////////////////////////// /// namespace nanoflann: NANOFLANN KD-tree adaptor for EIGEN /// namespace RigidMotionEstimator: functions to compute the rigid motion /// namespace SICP: sparse ICP implementation /// namespace ICP: reweighted ICP implementation /////////////////////////////////////////////////////////////////////////////// #ifndef ICP_H #define ICP_H #include #include #include #include #include #include #include #define TUPLE_SCALE 0.95 #define TUPLE_MAX_CNT 1000 /////////////////////////////////////////////////////////////////////////////// namespace nanoflann { /// KD-tree adaptor for working with data directly stored in an Eigen Matrix, without duplicating the data storage. /// This code is adapted from the KDTreeEigenMatrixAdaptor class of nanoflann.hpp template struct KDTreeAdaptor { typedef KDTreeAdaptor self_t; typedef typename MatrixType::Scalar num_t; typedef typename Distance::template traits::distance_t metric_t; typedef KDTreeSingleIndexAdaptor< metric_t, self_t, DIM, IndexType> index_t; index_t* index; KDTreeAdaptor(const MatrixType &mat, const int leaf_max_size = 10) : m_data_matrix(mat) { const size_t dims = mat.rows(); index = new index_t(dims, *this, nanoflann::KDTreeSingleIndexAdaptorParams(leaf_max_size, dims)); index->buildIndex(); } ~KDTreeAdaptor() { delete index; } const MatrixType &m_data_matrix; /// Query for the num_closest closest points to a given point (entered as query_point[0:dim-1]). inline void query(const num_t *query_point, const size_t num_closest, IndexType *out_indices, num_t *out_distances_sq) const { nanoflann::KNNResultSet resultSet(num_closest); resultSet.init(out_indices, out_distances_sq); index->findNeighbors(resultSet, query_point, nanoflann::SearchParams()); } /// Query for the closest points to a given point (entered as query_point[0:dim-1]). inline IndexType closest(const num_t *query_point) const { IndexType out_indices; num_t out_distances_sq; query(query_point, 1, &out_indices, &out_distances_sq); return out_indices; } const self_t & derived() const { return *this; } self_t & derived() { return *this; } inline size_t kdtree_get_point_count() const { return m_data_matrix.cols(); } /// Returns the distance between the vector "p1[0:size-1]" and the data point with index "idx_p2" stored in the class: inline num_t kdtree_distance(const num_t *p1, const size_t idx_p2, size_t size) const { num_t s = 0; for (size_t i = 0; i bool kdtree_get_bbox(BBOX&) const { return false; } }; } /////////////////////////////////////////////////////////////////////////////// /// Compute the rigid motion for point-to-point and point-to-plane distances namespace RigidMotionEstimator { /// @param Source (one 3D point per column) /// @param Target (one 3D point per column) /// @param Confidence weights template Eigen::Affine3d point_to_point(Eigen::MatrixBase& X, Eigen::MatrixBase& Y, const Eigen::MatrixBase& w) { int dim = X.rows(); /// Normalize weight vector Eigen::VectorXd w_normalized = w / w.sum(); /// De-mean Eigen::VectorXd X_mean(dim), Y_mean(dim); for (int i = 0; i svd(sigma, Eigen::ComputeFullU | Eigen::ComputeFullV); if (svd.matrixU().determinant()*svd.matrixV().determinant() < 0.0) { VectorX S = VectorX::Ones(dim); S(dim-1) = -1.0; transformation.linear() = svd.matrixV()*S.asDiagonal()*svd.matrixU().transpose(); } else { transformation.linear() = svd.matrixV()*svd.matrixU().transpose(); } transformation.translation() = Y_mean - transformation.linear()*X_mean; /// Re-apply mean X.colwise() += X_mean; Y.colwise() += Y_mean; /// Apply transformation // X = transformation*X; /// Return transformation return transformation; } /// @param Source (one 3D point per column) /// @param Target (one 3D point per column) template inline Eigen::Affine3d point_to_point(Eigen::MatrixBase& X, Eigen::MatrixBase& Y) { return point_to_point(X, Y, Eigen::VectorXd::Ones(X.cols())); } /// @param Source (one 3D point per column) /// @param Target (one 3D point per column) /// @param Target normals (one 3D normal per column) /// @param Confidence weights /// @param Right hand side template Eigen::Affine3d point_to_plane(Eigen::MatrixBase& X, Eigen::MatrixBase& Y, Eigen::MatrixBase& N, const Eigen::MatrixBase& w, const Eigen::MatrixBase& u) { typedef Eigen::Matrix Matrix66; typedef Eigen::Matrix Vector6; typedef Eigen::Block Block33; /// Normalize weight vector Eigen::VectorXd w_normalized = w / w.sum(); /// De-mean Eigen::Vector3d X_mean; for (int i = 0; i<3; ++i) X_mean(i) = (X.row(i).array()*w_normalized.transpose().array()).sum(); X.colwise() -= X_mean; Y.colwise() -= X_mean; /// Prepare LHS and RHS Matrix66 LHS = Matrix66::Zero(); Vector6 RHS = Vector6::Zero(); Block33 TL = LHS.topLeftCorner<3, 3>(); Block33 TR = LHS.topRightCorner<3, 3>(); Block33 BR = LHS.bottomRightCorner<3, 3>(); Eigen::MatrixXd C = Eigen::MatrixXd::Zero(3, X.cols()); #pragma omp parallel { #pragma omp for for (int i = 0; i().rankUpdate(C.col(i), w(i)); #pragma omp section for (int i = 0; i().rankUpdate(N.col(i), w(i)); #pragma omp section for (int i = 0; i() += C.col(i)*dist_to_plane; RHS.tail<3>() += N.col(i)*dist_to_plane; } } } LHS = LHS.selfadjointView(); /// Compute transformation Eigen::Affine3d transformation; Eigen::LDLT ldlt(LHS); RHS = ldlt.solve(RHS); transformation = Eigen::AngleAxisd(RHS(0), Eigen::Vector3d::UnitX()) * Eigen::AngleAxisd(RHS(1), Eigen::Vector3d::UnitY()) * Eigen::AngleAxisd(RHS(2), Eigen::Vector3d::UnitZ()); transformation.translation() = RHS.tail<3>(); /// Apply transformation X = transformation*X; /// Re-apply mean X.colwise() += X_mean; Y.colwise() += X_mean; transformation.translation() += -transformation.linear() * X_mean + X_mean; /// Return transformation return transformation; } /// @param Source (one 3D point per column) /// @param Target (one 3D point per column) /// @param Target normals (one 3D normal per column) /// @param Confidence weights template inline Eigen::Affine3d point_to_plane(Eigen::MatrixBase& X, Eigen::MatrixBase& Yp, Eigen::MatrixBase& Yn, const Eigen::MatrixBase& w) { return point_to_plane(X, Yp, Yn, w, Eigen::VectorXd::Zero(X.cols())); } } /////////////////////////////////////////////////////////////////////////////// /// ICP implementation using ADMM/ALM/Penalty method namespace SICP { struct Parameters { bool use_penalty = false; /// if use_penalty then penalty method else ADMM or ALM (see max_inner) double p = 1.0; /// p norm double mu = 10.0; /// penalty weight double alpha = 1.2; /// penalty increase factor double max_mu = 1e5; /// max penalty int max_icp = 100; /// max ICP iteration int max_outer = 100; /// max outer iteration int max_inner = 1; /// max inner iteration. If max_inner=1 then ADMM else ALM double stop = 1e-5; /// stopping criteria bool print_icpn = false; /// (debug) print ICP iteration Eigen::Matrix4d init_trans = Eigen::Matrix4d::Identity(); Eigen::Matrix4d gt_trans = Eigen::Matrix4d::Identity(); bool has_groundtruth = false; int convergence_iter = 0; double convergence_mse = 0.0; double convergence_gt_mse = 0.0; Eigen::Matrix4d res_trans = Eigen::Matrix4d::Identity(); std::string file_err = ""; std::string out_path = ""; int total_iters = 0; }; /// Shrinkage operator (Automatic loop unrolling using template) template inline double shrinkage(double mu, double n, double p, double s) { return shrinkage(mu, n, p, 1.0 - (p / mu)*std::pow(n, p - 2.0)*std::pow(s, p - 1.0)); } template<> inline double shrinkage<0>(double, double, double, double s) { return s; } /// 3D Shrinkage for point-to-point template inline void shrink(Eigen::Matrix3Xd& Q, double mu, double p) { double Ba = std::pow((2.0 / mu)*(1.0 - p), 1.0 / (2.0 - p)); double ha = Ba + (p / mu)*std::pow(Ba, p - 1.0); #pragma omp parallel for for (int i = 0; i ha) w = shrinkage(mu, n, p, (Ba / n + 1.0) / 2.0); Q.col(i) *= w; } } /// 1D Shrinkage for point-to-plane template inline void shrink(Eigen::VectorXd& y, double mu, double p) { double Ba = std::pow((2.0 / mu)*(1.0 - p), 1.0 / (2.0 - p)); double ha = Ba + (p / mu)*std::pow(Ba, p - 1.0); #pragma omp parallel for for (int i = 0; i ha) s = shrinkage(mu, n, p, (Ba / n + 1.0) / 2.0); y(i) *= s; } } /// Sparse ICP with point to point /// @param Source (one 3D point per column) /// @param Target (one 3D point per column) /// @param Parameters template void point_to_point(Eigen::MatrixBase& X, Eigen::MatrixBase& Y, Eigen::Vector3d& source_mean, Eigen::Vector3d& target_mean, Parameters& par) { /// Build kd-tree nanoflann::KDTreeAdaptor, 3, nanoflann::metric_L2_Simple> kdtree(Y); /// Buffers Eigen::Matrix3Xd Q = Eigen::Matrix3Xd::Zero(3, X.cols()); Eigen::Matrix3Xd Z = Eigen::Matrix3Xd::Zero(3, X.cols()); Eigen::Matrix3Xd C = Eigen::Matrix3Xd::Zero(3, X.cols()); Eigen::Matrix3Xd ori_X = X; Eigen::Affine3d T(par.init_trans); Eigen::Matrix3Xd X_gt; int nPoints = X.cols(); X = T * X; Eigen::Matrix3Xd Xo1 = X; Eigen::Matrix3Xd Xo2 = X; double gt_mse = 0.0, run_time; double begin_time, end_time; std::vector gt_mses, times; if(par.has_groundtruth) { Eigen::Vector3d temp_trans = par.gt_trans.block(0, 3, 3, 1); X_gt = ori_X; X_gt.colwise() += source_mean; X_gt = par.gt_trans.block(0, 0, 3, 3) * X_gt; X_gt.colwise() += temp_trans - target_mean; } begin_time = omp_get_wtime(); /// ICP int icp; for (icp = 0; icp void point_to_plane(Eigen::MatrixBase& X, Eigen::MatrixBase& Y, Eigen::MatrixBase& N, Eigen::Vector3d source_mean, Eigen::Vector3d target_mean, Parameters &par) { /// Build kd-tree nanoflann::KDTreeAdaptor, 3, nanoflann::metric_L2_Simple> kdtree(Y); /// Buffers Eigen::Matrix3Xd Qp = Eigen::Matrix3Xd::Zero(3, X.cols()); Eigen::Matrix3Xd Qn = Eigen::Matrix3Xd::Zero(3, X.cols()); Eigen::VectorXd Z = Eigen::VectorXd::Zero(X.cols()); Eigen::VectorXd C = Eigen::VectorXd::Zero(X.cols()); Eigen::Matrix3Xd ori_X = X; Eigen::Affine3d T(par.init_trans); Eigen::Matrix3Xd X_gt; int nPoints = X.cols(); X = T*X; Eigen::Matrix3Xd Xo1 = X; Eigen::Matrix3Xd Xo2 = X; double gt_mse = 0.0, run_time; double begin_time, end_time; std::vector gt_mses, times; if(par.has_groundtruth) { Eigen::Vector3d temp_trans = par.gt_trans.block(0, 3, 3, 1); X_gt = ori_X; X_gt.colwise() += source_mean; X_gt = par.gt_trans.block(0, 0, 3, 3) * X_gt; X_gt.colwise() += temp_trans - target_mean; } begin_time = omp_get_wtime(); /// ICP int icp; int total_iters = 0; for (icp = 0; icp p) r(i) = 0.0; else r(i) = std::pow((1.0 - std::pow(r(i) / p, 2.0)), 2.0); } } /// @param Residuals /// @param Parameter void fair_weight(Eigen::VectorXd& r, double p) { for (int i = 0; i &left, const std::pair &right) { return left.second < right.second; } }; /// @param Residuals /// @param Parameter void trimmed_weight(Eigen::VectorXd& r, double p) { std::vector > sortedDist(r.rows()); for (int i = 0; i(i, r(i)); } std::sort(sortedDist.begin(), sortedDist.end(), sort_pred()); r.setZero(); int nbV = r.rows()*p; for (int i = 0; i p) w = 0.0; else w = std::pow((1.0 - std::pow(r(i) / p, 2.0)), 2.0); energy += (r(i)*r(i))*w; } return energy; } /// @param Residuals /// @param Parameter double fair_energy(Eigen::VectorXd& r, double p) { double energy = 0; for (int i = 0; i > sortedDist(r.rows()); for (int i = 0; i(i, r(i)); } std::sort(sortedDist.begin(), sortedDist.end(), sort_pred()); Eigen::VectorXd t = r; t.setZero(); double energy = 0; int nbV = r.rows()*p; for (int i = 0; i Vector3; typedef Eigen::Matrix Vector6; typedef Eigen::Matrix Matrix3; typedef Eigen::Matrix Matrix4; typedef Eigen::Matrix VectorX; typedef Eigen::Matrix Matrix6X; ///aaicp /////////////////////////////////////////////////////////////////////////////////////////// Vector6 Matrix42Vector6 (const Matrix4 m) { Vector6 v; Matrix3 s = m.block(0,0,3,3); v.head(3) = s.eulerAngles(0, 1, 2); v.tail(3) = m.col(3).head(3); return v; } /////////////////////////////////////////////////////////////////////////////////////////// Matrix4 Vector62Matrix4 (const Vector6 v) { Matrix3 s (Eigen::AngleAxis(v(0), Vector3::UnitX()) * Eigen::AngleAxis(v(1), Vector3::UnitY()) * Eigen::AngleAxis(v(2), Vector3::UnitZ())); Matrix4 m = Matrix4::Zero(); m.block(0,0,3,3) = s; m(3,3) = 1; m.col(3).head(3) = v.tail(3); return m; } /////////////////////////////////////////////////////////////////////////////////////////// int alphas_cond (VectorX alphas) { double alpha_limit_min_ = -10; double alpha_limit_max_ = 10; return alpha_limit_min_ < alphas.minCoeff() && alphas.maxCoeff() < alpha_limit_max_ && alphas(alphas.size()-1) > 0; } /////////////////////////////////////////////////////////////////////////////////////////// VectorX get_alphas_lstsq (const Matrix6X f) { Matrix6X A = f.leftCols(f.cols()-1); A *= -1; A += f.rightCols(1) * VectorX::Constant(f.cols()-1, 1).transpose(); VectorX sol = A.colPivHouseholderQr().solve(f.rightCols(1)); sol.conservativeResize(sol.size()+1); sol[sol.size()-1] = 0; sol[sol.size()-1] = 1-sol.sum(); return sol; } /////////////////////////////////////////////////////////////////////////////////////////// VectorX get_next_u (const Matrix6X u, const Matrix6X g, const Matrix6X f, std::vector & save_alphas) { int i = 1; double beta_ = 1.0; save_alphas.clear(); Vector6 sol = ((1-beta_)*u.col(u.cols()-1) + beta_*g.col(g.cols()-1)); VectorX sol_alphas(1); sol_alphas << 1; i = 2; for (; i <= f.cols(); i++) { VectorX alphas = get_alphas_lstsq(f.rightCols(i)); if (!alphas_cond(alphas)) { break; } sol = (1-beta_)*u.rightCols(i)*alphas + beta_*g.rightCols(i)*alphas; sol_alphas = alphas; } for(int i= 0; i void point_to_point_aaicp(Eigen::MatrixBase& X,Eigen::MatrixBase& Y, Eigen::MatrixBase& source_mean, Eigen::MatrixBase& target_mean, ICP::Parameters& par) { /// Build kd-tree nanoflann::KDTreeAdaptor, 3, nanoflann::metric_L2_Simple> kdtree(Y); /// Buffers Eigen::Matrix3Xd Q = Eigen::Matrix3Xd::Zero(3, X.cols()); Eigen::VectorXd W = Eigen::VectorXd::Zero(X.cols()); Eigen::Matrix3Xd ori_X = X; double prev_energy = std::numeric_limits::max(), energy = std::numeric_limits::max(); Eigen::Affine3d T; if(par.use_init) { T.linear() = par.init_trans.block(0,0,3,3); T.translation() = par.init_trans.block(0,3,3,1); } else T = Eigen::Affine3d::Identity(); Eigen::Matrix3Xd X_gt = X; ///stop criterion paras MatrixXX To1 =T.matrix(); MatrixXX To2 = T.matrix(); ///AA paras Matrix6X u(6,0), g(6,0), f(6,0); Vector6 u_next, u_k; Matrix4 transformation = Matrix4::Identity(); Matrix4 final_transformation = Matrix4::Identity(); ///output para std::vector times, energys, gt_mses; double gt_mse; double begin_time, end_time, run_time; begin_time = omp_get_wtime(); ///output coeffs std::vector> coeffs; coeffs.clear(); std::vector alphas; X = T * X; ///groud truth target point cloud if(par.has_groundtruth) { Eigen::Vector3d temp_trans = par.gt_trans.block(0, 3, 3, 1); X_gt = ori_X; X_gt.colwise() += source_mean; X_gt = par.gt_trans.block(0, 0, 3, 3) * X_gt; X_gt.colwise() += temp_trans - target_mean; } ///begin ICP int icp = 0; for (; icp par.error_overflow_threshold_) { u_next = u_k = g.rightCols(1); prev_energy = std::numeric_limits::max(); u = u.rightCols(2); g = g.rightCols(1); f = f.rightCols(1); } else { prev_energy = energy; g.conservativeResize(g.rows(),g.cols()+1); g.col(g.cols()-1) = g_k; Vector6 f_k = g_k - u_k; f.conservativeResize(f.rows(),f.cols()+1); f.col(f.cols()-1) = f_k; u_next = get_next_u(u, g, f, alphas); u.conservativeResize(u.rows(),u.cols()+1); u.col(u.cols()-1) = u_next; u_k = u_next; accept_aa = true; } } ///init else { // Calculate energy W = (X - Q).colwise().norm(); prev_energy = get_energy(par.f, W, par.p); Vector6 u0 = Matrix42Vector6(Matrix4::Identity()); u.conservativeResize(u.rows(),u.cols()+1); u.col(0)=u0; Vector6 u1 = Matrix42Vector6(transformation * final_transformation); g.conservativeResize(g.rows(),g.cols()+1); g.col(0)=u1; u.conservativeResize(u.rows(),u.cols()+1); u.col(1)=u1; f.conservativeResize(f.rows(),f.cols()+1); f.col(0)=u1 - u0; u_next = u1; u_k = u1; energy = prev_energy; } transformation = Vector62Matrix4(u_next)*(final_transformation.inverse()); final_transformation = Vector62Matrix4(u_next); X = final_transformation.block(0,0,3,3) * ori_X; Vector3 trans = final_transformation.block(0,3,3,1); X.colwise() += trans; energys.push_back(energy); if (par.print_energy) std::cout << "icp iter = " << icp << ", Energy = " << energy << ", gt_mse = " << gt_mse<< std::endl; /// Stopping criteria double stop2 = (final_transformation - To2).norm(); To2 = final_transformation; if (stop2 < par.stop && icp) break; } W = (X - Q).colwise().norm(); double last_energy = get_energy(par.f, W, par.p); gt_mse = pow((X - X_gt).norm(),2) / X.cols(); final_transformation.block(0,3,3,1) += -final_transformation.block(0, 0, 3, 3)*source_mean + target_mean; X.colwise() += target_mean; ///save convergence result par.convergence_energy = last_energy; par.convergence_gt_mse = gt_mse; par.convergence_iter = icp; par.res_trans = final_transformation; ///output if (par.print_output) { std::ofstream out_res(par.out_path); if (!out_res.is_open()) { std::cout << "Can't open out file " << par.out_path << std::endl; } ///output time and energy out_res.precision(16); for (int i = 0; i