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;
}
//計算雅可比矩陣
//雅可比矩陣為[I,-P'^]
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));
}