3D-3D:ICP估计姿态

1.ICP

假设有一组配对好的3D点, \(P={P_{1}, ..., P_{N}}\) , \(P^{'}={P_{1}^{'}, ..., P_{N}^{'}}\)。
有一个欧式变换R,t,使得: $ p_{i} = Rp^{'}_{i} + t $
该问题可以用迭代最近点(ICP)来求解。注意考虑两组3D点的变换时,和相机没有关系。
ICP求解线性代数的求解(SVD)和非线性优化方式求解(类似于BA)

2.SVD求解:

定义误差项: \(e_{i} = p_{i} - ( Rp^{'}_{i} + t )\)
构建最小二乘问题,使误差平方和达到极小的R,t
定义两组点的质心:
\(p = \frac{1}{n} \sum^{n}_{i=1} (p_{i}), p^{'} = \frac{1}{n} \sum^{n}_{i=1} (p_{i}^{'}),\)

步骤:

  • 计算两组点的质心位置 \(p,p^{'}\),然后再计算每个点的去质心坐标:
    \(q_{i} = p_{i} - p, q_{i}^{'} = p_{i}^{'} - p^{'}\)

  • 计算 \(R^{*} = argmin \frac{1}{2} \sum^{n}_{i=1} || q_{i} - Rq_{i}^{'} ||^{2}\)

  • 将上式展开,优化函数变为求解 \(-tr( R \sum^{n}_{i=1} q_{i}^{'} q_{i}^{T} )\)
    定义 \(W=\sum^{n}_{i=1} q_{i}^{'} q_{i}^{T}\),对W进行SVD分解,得到\(W=U \Sigma V^{T}\)

  • \Sigma 为奇异值组成的对角矩阵,对角线元素从大到小排列,而U和V为正交矩阵。当W满秩时,\(R=UV^{T}\)

  • 根据求出的R,计算t: \(t^{*} = p - Rp^{'}\)

3.代码:

void pose_estimation_3d3d(const vector<Point3f> &pts1,
                          const vector<Point3f> &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<Point3f> 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<Eigen::Matrix3d> 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_<double>(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_<double>(3, 1) << t_(0, 0), t_(1, 0), t_(2, 0));
}

4.非线性优化方法:

/// 节点,优化变量维度和数据类型
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<double, 6, 1> 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 {}
};

/// 边,误差模型      观测维度,观测数据类型,  链接节点类型
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<const VertexPose *> ( _vertices[0] );
	//计算误差,测量值-转换值
    _error = _measurement - pose->estimate() * _point;
  }

  //计算雅可比矩阵
  virtual void linearizeOplus() override {
    VertexPose *pose = static_cast<VertexPose *>(_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;
};

//将顶点和边加入g2o
oid bundleAdjustment(
  const vector<Point3f> &pts1,
  const vector<Point3f> &pts2,
  Mat &R, Mat &t) {
  // 构建图优化,先设定g2o
  typedef g2o::BlockSolverX BlockSolverType;
  typedef g2o::LinearSolverDense<BlockSolverType::PoseMatrixType> LinearSolverType; // 线性求解器类型
  // 梯度下降方法,可以从GN, LM, DogLeg 中选
  auto solver = new g2o::OptimizationAlgorithmLevenberg(
    g2o::make_unique<BlockSolverType>(g2o::make_unique<LinearSolverType>()));
  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<double> time_used = chrono::duration_cast<chrono::duration<double>>(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_<double>(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_<double>(3, 1) << t_(0, 0), t_(1, 0), t_(2, 0));
}

上一篇:cartographer的后端核心,后端优化OptimizationProblem2D::Solve


下一篇:We go for our interest in drawing manga characters.