视觉SLAM的前端也就是视觉里程计实际上要解决的问题是根据匹配的特征点估计相机运动。根据不同的已知条件,选择不同的方法。
1.针对单目相机2D-2D:对极几何
对于单目相机,前后两幅图像之间存在着对极几何约束,我们掌握的信息只有两幅图像中特征点的图像坐标,因此相机运动估计问题变为以下两步:
(1)根据匹配点坐标估计本质矩阵E:因为本质矩阵E仅与旋转矩阵R和平移向量t有关,估计本质矩阵的方法包括传统的八点法和RANSAC(随机抽样一致性算法)及其改进算法MASC等。实际上当匹配点对较多时,随机抽样算法效果应该是更好的。
(2)通过分解本质矩阵E得到相机运动对应的R和t:可以使用奇异值分解算法(SVD)。
上述过程在示例代码中完全使用的是OpenCV中封装好的函数,比较简单,就不赘述了。
2.双目相机或者RGB-D相机3D-2D:PnP
对于双目相机或者RGB-D相机我们可以得到特征点的深度,也就能确定特征点在相机坐标系下的坐标。如果两张图像中一张特征点的3D位置已知就可以使用PnP估计相机的运动,通过光束平差法(BA)最小化重投影误差求解相机运动参数的最优解。
直接看示例代码的思路:
(1)首先要得到图像1和图像2的特征点及匹配结果,这一步比较简单。
(2)根据深度图得到图像1中特征点在相机坐标系下的三维坐标。此时可以认为将图像1时刻的相机坐标系与世界坐标系重合,实际上是求解2时刻相对1时刻的运动参数。
// 建立3D点
// 深度图为16位无符号数,单通道图像
Mat d1 = imread("/home/svv12138/Downloads/slambook2-master/ch7/1_depth.png");
//内参矩阵
Mat K = (Mat_(3, 3) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1);
vector pts_3d;
vector pts_2d;
for (DMatch m:matches) {
ushort d = d1.ptr(int(keypoints_1[m.queryIdx].pt.y[int(keypoints_1[m.queryIdx].pt.x)];
if (d == 0) // bad depth
continue;
float dd = d / 5000.0;
//转化到归一化坐标
Point2d p1 = pixel2cam(keypoints_1[m.queryIdx].pt, K);
//乘以深度,转化到世界坐标系下,此时世界坐标系与一号相机坐标系重合
pts_3d.push_back(Point3f(p1.x * dd, p1.y * dd, dd));
//对应点在2视角下的投影坐标
pts_2d.push_back(keypoints_2[m.trainIdx].pt);
}
(3)最小化重投影误差得到最优解
(a)手写的高斯-牛顿法:
void bundleAdjustmentGaussNewton(
const VecVector3d &points_3d,//3D点坐标
const VecVector2d &points_2d,//对应图像平面坐标
const Mat &K,//内参矩阵
Sophus::SE3d &pose) {
typedef Eigen::Matrix Vector6d;
//迭代次数
const int iterations = 10;
double cost = 0, lastCost = 0;
//内部参数
double fx = K.at(0, 0);
double fy = K.at(1, 1);
double cx = K.at(0, 2);
double cy = K.at(1, 2);
for (int iter = 0; iter < iterations; iter++) {
//Hessian矩阵
Eigen::Matrix H = Eigen::Matrix::Zero();
//b矩阵
Vector6d b = Vector6d::Zero();
cost = 0;
// compute cost
for (int i = 0; i < points_3d.size(); i++) {
//转化到相机坐标系
Eigen::Vector3d pc = pose * points_3d[i];
//1/z
double inv_z = 1.0 / pc[2];
double inv_z2 = inv_z * inv_z;
//3D点的重投影误差
Eigen::Vector2d proj(fx * pc[0] / pc[2] + cx, fy * pc[1] / pc[2] + cy);
Eigen::Vector2d e = points_2d[i] - proj;
//计算代价函数
cost += e.squaredNorm();
//Jacobian矩阵
Eigen::Matrix J;
//导数矩阵
J << -fx * inv_z,
0,
fx * pc[0] * inv_z2,
fx * pc[0] * pc[1] * inv_z2,
-fx - fx * pc[0] * pc[0] * inv_z2,
fx * pc[1] * inv_z,
0,
-fy * inv_z,
fy * pc[1] * inv_z2,
fy + fy * pc[1] * pc[1] * inv_z2,
-fy * pc[0] * pc[1] * inv_z2,
-fy * pc[0] * inv_z;
//计算增量方程
H += J.transpose() * J;
b += -J.transpose() * e;
}
Vector6d dx;
//求解增量方程 确定增量
dx = H.ldlt().solve(b);
if (isnan(dx[0])) {
cout << "result is nan!" << endl;
break;
}
if (iter > 0 && cost >= lastCost) {
// cost increase, update is not good
cout << "cost: " << cost << ", last cost: " << lastCost << endl;
break;
}
// 更新变换矩阵:指数映射
pose = Sophus::SE3d::exp(dx) * pose;
//记录代价函数
lastCost = cost;
cout << "iteration " << iter << " cost=" << std::setprecision(12) << cost << endl;
if (dx.norm() < 1e-6) {
// converge
break;
}
}
cout << "pose by g-n: \n" << pose.matrix() << endl;
}
(b)使用G2O图优化算法:
// 定义节点
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 {}
};
/// 定义边:一元边、观测值维度2(重投影误差)、连接节点类型
class EdgeProjection : public g2o::BaseUnaryEdge<2, Eigen::Vector2d, VertexPose> {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
EdgeProjection(const Eigen::Vector3d &pos, const Eigen::Matrix3d &K) : _pos3d(pos), _K(K) {}
//误差计算:重投影误差
virtual void computeError() override {
const VertexPose *v = static_cast (_vertices[0]);
Sophus::SE3d T = v->estimate();
Eigen::Vector3d pos_pixel = _K * (T * _pos3d);
pos_pixel /= pos_pixel[2];
_error = _measurement - pos_pixel.head<2>();
}
//计算雅可比矩阵
virtual void linearizeOplus() override {
const VertexPose *v = static_cast (_vertices[0]);
Sophus::SE3d T = v->estimate();
Eigen::Vector3d pos_cam = T * _pos3d;
double fx = _K(0, 0);
double fy = _K(1, 1);
double cx = _K(0, 2);
double cy = _K(1, 2);
double X = pos_cam[0];
double Y = pos_cam[1];
double Z = pos_cam[2];
double Z2 = Z * Z;
_jacobianOplusXi
<< -fx / Z, 0, fx * X / Z2, fx * X * Y / Z2, -fx - fx * X * X / Z2, fx * Y / Z,
0, -fy / Z, fy * Y / (Z * Z), fy + fy * Y * Y / Z2, -fy * X * Y / Z2, -fy * X / Z;
}
virtual bool read(istream &in) override {}
virtual bool write(ostream &out) const override {}
private:
Eigen::Vector3d _pos3d;
Eigen::Matrix3d _K;
};
void bundleAdjustmentG2O(
const VecVector3d &points_3d,
const VecVector2d &points_2d,
const Mat &K,
Sophus::SE3d &pose) {
// 构建图优化,先设定g2o
//优化变量维度是6,误差值维度3
typedef g2o::BlockSolver> BlockSolverType;
// 线性求解器类型
typedef g2o::LinearSolverDense LinearSolverType;
// 梯度下降方法,可以从GN, LM, DogLeg 中选
auto solver = new g2o::OptimizationAlgorithmGaussNewton(
g2o::make_unique(g2o::make_unique()));
g2o::SparseOptimizer optimizer; // 图模型
optimizer.setAlgorithm(solver); // 设置求解器
optimizer.setVerbose(true); // 打开调试输出
// 添加节点:1个 摄像机位姿
VertexPose *vertex_pose = new VertexPose();
vertex_pose->setId(0);
vertex_pose->setEstimate(Sophus::SE3d());
optimizer.addVertex(vertex_pose);
// K
Eigen::Matrix3d K_eigen;
K_eigen <<
K.at(0, 0), K.at(0, 1), K.at(0, 2),
K.at(1, 0), K.at(1, 1), K.at(1, 2),
K.at(2, 0), K.at(2, 1), K.at(2, 2);
// 添加边:每对匹配点就是一个边
int index = 1;
for (size_t i = 0; i < points_2d.size(); ++i) {
auto p2d = points_2d[i];
auto p3d = points_3d[i];
EdgeProjection *edge = new EdgeProjection(p3d, K_eigen);
edge->setId(index);
edge->setVertex(0, vertex_pose);
edge->setMeasurement(p2d);
edge->setInformation(Eigen::Matrix2d::Identity());
optimizer.addEdge(edge);
index++;
}
chrono::steady_clock::time_point t1 = chrono::steady_clock::now();
optimizer.setVerbose(true);
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 << "pose estimated by g2o =\n" << vertex_pose->estimate().matrix() << endl;
pose = vertex_pose->estimate();
}
3.3D-3D:ICP
当我们有多对匹配好的3D点时,可以使用ICP(迭代最近点)估计相机位姿。求解方法也包括两种SVD算法和非线性优化算。这里主要看一下SVD方法的实现:
void pose_estimation_3d3d(const vector &pts1,
const vector &pts2,
Mat &R, Mat &t) {
//质心 公式7.51
Point3f p1, p2;
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;
}
//计算W矩阵 公式7.57
// 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;
// 奇异值分解 公式7.58
// 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;
//计算得到R矩阵 公式7.59
Eigen::Matrix3d R_ = U * (V.transpose());
//计算行列式 <0则取负
if (R_.determinant() < 0) {
R_ = -R_;
}
//计算平移向量t 公式7.54
Eigen::Vector3d t_ = Eigen::Vector3d(p1.x, p1.y, p1.z) - R_ * Eigen::Vector3d(p2.x, p2.y, p2.z);
//输出设置为Mat数据类型
// 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));
}
纵观三种情况下的多种求解方式,本质上都是利用匹配好的特征点,以最小化重投影误差(无论是三维空间下的还是二维图像下的)为目标,使用优化算法求解相机运动参数。