这篇文章针对有一定SLAM基础的同学或者对李群李代数的应用感兴趣的数学专业同学,已经很小众了,但对于真正干这行并想要更深理解的同学可能会很有帮助,因此花了些时间整理发出来。要从理论推导到后面代码应用都读懂难度还是比较大,尽量讲解。
下面是激动人心的实际应用
有了李群的导数,接下来就是实际应用部分了。 我这里的实际应用不是说让你自己写几行代码去实现,而是去看看比较成熟的SLAM系统是在哪里用到上面的推导的。这需要你打开相关的论文和代码对比来看,需要些精力。我经常操作的是视觉惯性slam,好的开源库有VINS-FUSION,VINS-Mono(都来自于港科大,前者更新有更强的应用不过后者被更多人熟知),okvis等。okvis是多年前的作品,非常经典,但是代码难度比前面的大不少。综合了一下情况我决定使用VINS-Mono的代码,把李代数的求导结果和他们的代码里一一对应起来。代码在他们的github中 HKUST-Aerial-Robotics/VINS-Mono: A Robust and … – GitHub 我们以VINS-Mono想要求解的reprojection error为例。 vins的原论文 VINS-Mono: A Robust and Versatile Monocular Visual … – arXiv 式25把处于不同图像的对应的2d点投影到同一单位球上然后求残差。 在vins-mono里projection_factor.cpp
里Evaluate
函数中包含了误差函数以及倒数的结果。 首先来看前面几行几个参数
Eigen::Vector3d Pi(parameters[0][0], parameters[0][1], parameters[0][2]);
Eigen::Quaterniond Qi(parameters[0][6], parameters[0][3], parameters[0][4], parameters[0][5]);
Eigen::Vector3d Pj(parameters[1][0], parameters[1][1], parameters[1][2]);
Eigen::Quaterniond Qj(parameters[1][6], parameters[1][3], parameters[1][4], parameters[1][5]);
Eigen::Vector3d tic(parameters[2][0], parameters[2][1], parameters[2][2]);
Eigen::Quaterniond qic(parameters[2][6], parameters[2][3], parameters[2][4], parameters[2][5]);
double inv_dep_i = parameters[3][0];
这几行的parameter来源于传入的要优化的参数,具体来源于在estimator.cpp中的这两行
ProjectionFactor *f = new ProjectionFactor(pts_i, pts_j);
problem.AddResidualBlock(f, loss_function, para_Pose[imu_i], para_Pose[imu_j], para_Ex_Pose[0], para_Feature[feature_index]);
para_Pose[imu_i]
对应于parameter[0],是IMUi
时刻的位姿,para_Pose[imu_j]
对应于parameter[1],是IMUj
时刻位姿,para_Ex_Pose[0]
是相机和IMU的外参,对应parameter[2]。最后一个就对应inv_dep_i
.即该像素点深度的倒数。这几个是想要被优化的量。随后几行
Eigen::Vector3d pts_camera_i = pts_i / inv_dep_i;
Eigen::Vector3d pts_imu_i = qic * pts_camera_i + tic;
Eigen::Vector3d pts_w = Qi * pts_imu_i + Pi;
Eigen::Vector3d pts_imu_j = Qj.inverse() * (pts_w - Pj);
Eigen::Vector3d pts_camera_j = qic.inverse() * (pts_imu_j - tic);
对应vins的原论文式25第三个
的求法。注意式子中的back projection函数
在原文中它的作用是
turns a pixel location into a unit vector using camera intrinsic parameters
。具体参见论文图6. 代码中的pts_i
对应的是公式中的
这是论文中所说的指向球面的
unit vector
。用它除以深度的倒数(乘上深度),就对应代码中的pts_i / inv_dep_i
,获得一个在相机坐标系下的3d点
这个3d点乘以相机到body(或者说IMU)坐标系下的转换矩阵得到在IMU坐标系下的坐标。
对应的代码中的
qic * pts_camera_i + tic
。剩下的式25的第3个式子的位姿变换和代码的每一行一一对应。上式用
转到世界坐标系,再转到
图像所在的坐标系最后转到
相机下的
unit vector
即pts_camera_j
.
随后 代码中
#ifdef UNIT_SPHERE_ERROR
residual = tangent_base * (pts_camera_j.normalized() - pts_j.normalized());
#else
double dep_j = pts_camera_j.z();
residual = (pts_camera_j / dep_j).head<2>() - pts_j.head<2>();
#endif
用UNIT_SPHERE_ERROR
才和式25的第一行对应,如果不用的话就和普通的pinhole相机模型的点对应。为了方便起见,我还是推导的不用UNIT_SPHERE_ERROR
所得到的雅各比矩阵。因为我发现VINS, parameter.h中的#define UNIT_SPHERE_ERROR
这一行被注释掉了。 代码下一行 residual = sqrt_info * residual;
okvis也有这一行,这是因为ceres能接受的最小二乘优化只能是最简单的形式
,而带有协方差的优化的形式为
,所以代码中会对
做LLT分解,有
,那个sqrt_info自然就是
了。 综上针对某一个像素点在
frame下的像素坐标我们的residual就是
式子中
来源于测量(比如我们通过特征点匹配的方法知道了i,j是对应的,那时得到的j的坐标就是通过测量得到的),
表示取向量第1位到第n位。把上式具体写出来就是
residual需要求导的对象是body在
frame时的pose,即
。 首先我们计算简单的对位置求导。
其中
为2维,
为3d点
,很容易得到
然后(8)式对
求导,得到
对应代码中的
jaco_i.leftCols<3>() = ric.transpose() * Rj.transpose();
即
这里用到了SO(3)群的基本性质,SO(3)下的矩阵的逆等于它的转置。 之后我们对旋转求导数
导数的前一部分和式10一样,后一部分涉及到李群的求导,为书写方便我们先令
,因为左式本来就是
frame像素点投影到相机平面的3d点。后一部分
现在只对
求导数,那其他量视为是常量,我们令
,另外3d点
得到的是body 坐标系下的3d点,我们记为
。那么上式就变成了
现在的问题就是如何得到
了,简单记为
。那这儿很明显了,应用我们右扰动的推导结果,可以直接得到
代入
,我们就有了
这和代码中的
jaco_i.rightCols<3>() = ric.transpose() * Rj.transpose() * Ri * -Utility::skewSymmetric(pts_imu_i);
对应。 总的来说代码第一个求导部分得到了残差对
frame处位姿的求导。
if (jacobians[0])
{
Eigen::Map<Eigen::Matrix<double, 2, 7, Eigen::RowMajor>> jacobian_pose_i(jacobians[0]);
Eigen::Matrix<double, 3, 6> jaco_i;
jaco_i.leftCols<3>() = ric.transpose() * Rj.transpose();\\对位移求导
jaco_i.rightCols<3>() = ric.transpose() * Rj.transpose() * Ri * -Utility::skewSymmetric(pts_imu_i);\\对旋转求导
jacobian_pose_i.leftCols<6>() = reduce * jaco_i;\\reduce为式10
jacobian_pose_i.rightCols<1>().setZero(); \\这里有一个0列,回顾前面可以发现我们在求偏导时忽略了一个1的
}