随手笔记——3D−3D:ICP求解

随手笔记——3D−3D:ICP求解

  • 使用 SVD 求解 ICP
  • 使用非线性优化来求解 ICP

原理参见 https://blog.csdn.net/jppdss/article/details/131919483

使用 SVD 求解 ICP

使用两幅 RGB-D 图像,通过特征匹配获取两组 3D 点,最后用 ICP 计算它们的位姿变换。

void pose_estimation_3d3d(const vector &pts1,
                          const vector &pts2,
                          Mat &R, Mat &t) {
  Point3f p1, p2;     // center of mass
  int N = pts1.size();
  for (int i = 0; i < N; i++) {
    p1 += pts1[i];
    p2 += pts2[i];
  }
  p1 = Point3f(Vec3f(p1) / N);
  p2 = Point3f(Vec3f(p2) / N);
  vector q1(N), q2(N); // remove the center
  for (int i = 0; i < N; i++) {
    q1[i] = pts1[i] - p1;
    q2[i] = pts2[i] - p2;
  }

  // compute q1*q2^T
  Eigen::Matrix3d W = Eigen::Matrix3d::Zero();
  for (int i = 0; i < N; i++) {
    W += Eigen::Vector3d(q1[i].x, q1[i].y, q1[i].z) * Eigen::Vector3d(q2[i].x, q2[i].y, q2[i].z).transpose();
  }
  cout << "W=" << W << endl;

  // SVD on W
  Eigen::JacobiSVD svd(W, Eigen::ComputeFullU | Eigen::ComputeFullV);
  Eigen::Matrix3d U = svd.matrixU();
  Eigen::Matrix3d V = svd.matrixV();

  cout << "U=" << U << endl;
  cout << "V=" << V << endl;

  Eigen::Matrix3d R_ = U * (V.transpose());
  if (R_.determinant() < 0) {
    R_ = -R_;
  }
  Eigen::Vector3d t_ = Eigen::Vector3d(p1.x, p1.y, p1.z) - R_ * Eigen::Vector3d(p2.x, p2.y, p2.z);

  // convert to cv::Mat
  R = (Mat_(3, 3) <<
    R_(0, 0), R_(0, 1), R_(0, 2),
    R_(1, 0), R_(1, 1), R_(1, 2),
    R_(2, 0), R_(2, 1), R_(2, 2)
  );
  t = (Mat_(3, 1) << t_(0, 0), t_(1, 0), t_(2, 0));
}

使用非线性优化来求解 ICP

使用两幅 RGB-D 图像,通过特征匹配获取两组 3D 点,最后用非线性优化计算它们的位姿变换。

/// vertex and edges used in g2o ba
class VertexPose : public g2o::BaseVertex<6, Sophus::SE3d> {
public:
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW;

  virtual void setToOriginImpl() override {
    _estimate = Sophus::SE3d();
  }

  /// left multiplication on SE3
  virtual void oplusImpl(const double *update) override {
    Eigen::Matrix update_eigen;
    update_eigen << update[0], update[1], update[2], update[3], update[4], update[5];
    _estimate = Sophus::SE3d::exp(update_eigen) * _estimate;
  }

  virtual bool read(istream &in) override {}

  virtual bool write(ostream &out) const override {}
};


/// g2o edge
class EdgeProjectXYZRGBDPoseOnly : public g2o::BaseUnaryEdge<3, Eigen::Vector3d, VertexPose> {
public:
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW;

  EdgeProjectXYZRGBDPoseOnly(const Eigen::Vector3d &point) : _point(point) {}

  virtual void computeError() override {
    const VertexPose *pose = static_cast ( _vertices[0] );
    _error = _measurement - pose->estimate() * _point;
  }

  virtual void linearizeOplus() override {
    VertexPose *pose = static_cast(_vertices[0]);
    Sophus::SE3d T = pose->estimate();
    Eigen::Vector3d xyz_trans = T * _point;
    _jacobianOplusXi.block<3, 3>(0, 0) = -Eigen::Matrix3d::Identity();
    _jacobianOplusXi.block<3, 3>(0, 3) = Sophus::SO3d::hat(xyz_trans);
  }

  bool read(istream &in) {}

  bool write(ostream &out) const {}

protected:
  Eigen::Vector3d _point;
};


void bundleAdjustment(
 const vector &pts1,
 const vector &pts2,
 Mat &R, Mat &t) {
 // 构建图优化,先设定g2o
 typedef g2o::BlockSolverX BlockSolverType;
 typedef g2o::LinearSolverDense LinearSolverType; // 线性求解器类型
 // 梯度下降方法,可以从GN, LM, DogLeg 中选
 auto solver = new g2o::OptimizationAlgorithmLevenberg(
   g2o::make_unique(g2o::make_unique()));
 g2o::SparseOptimizer optimizer;     // 图模型
 optimizer.setAlgorithm(solver);   // 设置求解器
 optimizer.setVerbose(true);       // 打开调试输出

 // vertex
 VertexPose *pose = new VertexPose(); // camera pose
 pose->setId(0);
 pose->setEstimate(Sophus::SE3d());
 optimizer.addVertex(pose);

 // edges
 for (size_t i = 0; i < pts1.size(); i++) {
   EdgeProjectXYZRGBDPoseOnly *edge = new EdgeProjectXYZRGBDPoseOnly(
     Eigen::Vector3d(pts2[i].x, pts2[i].y, pts2[i].z));
   edge->setVertex(0, pose);
   edge->setMeasurement(Eigen::Vector3d(
     pts1[i].x, pts1[i].y, pts1[i].z));
   edge->setInformation(Eigen::Matrix3d::Identity());
   optimizer.addEdge(edge);
 }

 chrono::steady_clock::time_point t1 = chrono::steady_clock::now();
 optimizer.initializeOptimization();
 optimizer.optimize(10);
 chrono::steady_clock::time_point t2 = chrono::steady_clock::now();
 chrono::duration time_used = chrono::duration_cast>(t2 - t1);
 cout << "optimization costs time: " << time_used.count() << " seconds." << endl;

 cout << endl << "after optimization:" << endl;
 cout << "T=\n" << pose->estimate().matrix() << endl;

 // convert to cv::Mat
 Eigen::Matrix3d R_ = pose->estimate().rotationMatrix();
 Eigen::Vector3d t_ = pose->estimate().translation();
 R = (Mat_(3, 3) <<
   R_(0, 0), R_(0, 1), R_(0, 2),
   R_(1, 0), R_(1, 1), R_(1, 2),
   R_(2, 0), R_(2, 1), R_(2, 2)
 );
 t = (Mat_(3, 1) << t_(0, 0), t_(1, 0), t_(2, 0));
}

注:以上仅供个人学习使用,如有侵权,请联系!

你可能感兴趣的:(SLAM,笔记)