SLAM--三角化测量

单目相机中2d特征点大多是通过三角测量求解出地图点的世界坐标

VINS中的三角测量

1. 推导

3D点齐次坐标 [ x , y , z , 1 ] T [x, y, z, 1]^{T} [x,y,z,1]T,3D点在图像中的投影:
λ [ u v 1 ] = K [ R ∣ t ] ⏟ P [ x y z 1 ] \lambda\left[\begin{array}{l}{u} \\ {v} \\ {1}\end{array}\right]=\underbrace{\mathbf{K}[\mathbf{R} | \mathbf{t}]}_{\mathbf{P}}\left[\begin{array}{l}{x} \\ {y} \\ {z} \\ {1}\end{array}\right] λuv1=P K[Rt]xyz1
λ u = P X \lambda \mathbf{u}=\mathbf{P} \mathbf{X} λu=PX
两边同时叉乘u,则有:
u ∧ P X = 0 \mathbf{u}^{\wedge} \mathbf{P X}=0 uPX=0
展开得:
[ 0 − 1 v 1 0 − u − v u 0 ] [ P 1 P 2 P 3 ] X = 0 \left[\begin{array}{ccc}{0} & {-1} & {v} \\ {1} & {0} & {-u} \\ {-v} & {u} & {0}\end{array}\right]\left[\begin{array}{l}{\mathbf{P}_{1}} \\ {\mathbf{P}_{2}} \\ {\mathbf{P}_{3}}\end{array}\right] \mathbf{X}=0 01v10uvu0P1P2P3X=0
{ ( v P 3 − P 2 ) X = 0 ( P 1 − u P 3 ) X = 0 ( u P 2 − v P 1 ) X = 0 \left\{\begin{array}{l}{\left(v \mathbf{P}_{3}-\mathbf{P}_{2}\right) \mathbf{X}=0} \\ {\left(\mathbf{P}_{1}-u \mathbf{P}_{3}\right) \mathbf{X}=0} \\ {\left(u \mathbf{P}_{2}-v \mathbf{P}_{1}\right) \mathbf{X}=0}\end{array}\right. (vP3P2)X=0(P1uP3)X=0(uP2vP1)X=0
由于(1)式和(2)式可以得到(3)式,故一帧图像可以得到2个独立线性方程,则两帧可以形成四个方程:
[ v 1 P 3 1 − P 2 1 u 1 P 3 1 − P 1 1 v 2 P 3 2 − P 2 2 u 2 P 3 2 − P 1 2 ] ⏟ P X = 0 \underbrace{\left[\begin{array}{l}{v_{1} \mathbf{P}_{3}^{1}-\mathbf{P}_{2}^{1}} \\ {u_{1} \mathbf{P}_{3}^{1}-\mathbf{P}_{1}^{1}} \\ {v_{2} \mathbf{P}_{3}^{2}-\mathbf{P}_{2}^{2}} \\ {u_{2} \mathbf{P}_{3}^{2}-\mathbf{P}_{1}^{2}}\end{array}\right]}_{\mathbf{P}}\mathbf{X}=0 P v1P31P21u1P31P11v2P32P22u2P32P12X=0

  • 这里可以使用SVD求解,齐次坐标X即为H的最小奇异值的奇异向量。

2. 代码

void FeatureManager::triangulatePoint(Eigen::Matrix<double, 3, 4> &Pose0, Eigen::Matrix<double, 3, 4> &Pose1,
                        Eigen::Vector2d &point0, Eigen::Vector2d &point1, Eigen::Vector3d &point_3d)
{
    Eigen::Matrix4d design_matrix = Eigen::Matrix4d::Zero();
    design_matrix.row(0) = point0[0] * Pose0.row(2) - Pose0.row(0);
    design_matrix.row(1) = point0[1] * Pose0.row(2) - Pose0.row(1);
    design_matrix.row(2) = point1[0] * Pose1.row(2) - Pose1.row(0);
    design_matrix.row(3) = point1[1] * Pose1.row(2) - Pose1.row(1);
    Eigen::Vector4d triangulated_point;
    triangulated_point =
              design_matrix.jacobiSvd(Eigen::ComputeFullV).matrixV().rightCols<1>();
    point_3d(0) = triangulated_point(0) / triangulated_point(3);
    point_3d(1) = triangulated_point(1) / triangulated_point(3);
    point_3d(2) = triangulated_point(2) / triangulated_point(3);
}

你可能感兴趣的:(VINS学习)