目录
简介
PNP(Perspective-n-Point)描述了当知道n个3D空间点及其投影位置时(2D),如何估计相机的位姿。如果两张图像中的一张特征点的3D位置已知,那么最少只需要3个点对就可以估计相机的运动。如果使用双目相机或者RGB-D相机(深度相机),则可以直接使用PNP来估计相机运动,如果是单目相机,则需要初始化。3D-2D方法不需要使用使用对极约束,又可以在较少的点中获得较好的运动估计,是一种最重要的姿态估计方法。
PNP问题有很多求解方法,例如P3P,直接线性变换(DLT),EPNP,UPNP。也可以用非线性优化的方法求解,也就是BA。
直接线性变换
假设有一个空间点P,我们知道它的世界齐次坐标(X,Y,Z,1)。在图像I中,投影到特征点x1=(u1,v1,1)。定义一个包含旋转和平移的增广矩阵[R|t]。那么P和x1的关系可以表示如下:
这里的t是我们的待求变量,每个特征点都可以提供两个线性约束,t一共是12维,那我们最少可以通过6对特征点来求T矩阵。当匹配点大于6对的时候可以使用SVD的方法对超定方程求最小二乘解。
P3P
p3p需要利用给定的3个点的几何关系,输入数据为3对3D-2D的点,其中3D的点为世界坐标系下的3个点,2D点为3D点对应在成像平面上的投影。P3P还需要一对验证点来从可能的解中选择正确的那个。如果3D点在相机坐标系下的点能够算出,则我们就得到了3D-3D的对应点,把PNP问题转换成ICP问题。
P3P虽然使用的匹配点少,但是也存在着一些问题:
1.当给定的匹配点多于3个的时候,难以利用更多的信息。
2.如果3D,2D点受到噪声的影响,或者误匹配,则算法失效。
在SLAM中,通常的做法是先用P3P/EPNP等方法估计相机位姿,再构建最小二乘优化问题对估计值进行调整。在相机足够连续时,也可以假设相机不动或匀速运动,用推测值作为初始值进行优化。
非线性优化:最小化重投影误差求解PNP
除了使用线性方法,我们还可以把PNP问题构建成一个关于重投影误差的非线性最小二乘问题。线性方法,往往是先求相机位姿,再求空间点位置,而非线性优化方法则是把它们都看成优化变量,放在一起优化。我们统称这种问题为BA。
假设有n个三维空间点P及其投影p,我们希望计算相机的位姿R,t。它的李群表示为T。像素位置与空间点位置 的关系如下(矩阵形式):
这个式子隐含了一次从齐次坐标到非齐次坐标的转换,否则按矩阵乘法来说,维度是不对的。由于观测点的噪声,所以该等式存在一个误差。因此,将误差求和,构建最小二乘问题。然后寻求最好的相机位姿,使误差最小化:
该问题的误差项,是将3D点的投影位置与观测位置作差,所以称为重投影误差。我们现在要调整相机的位姿,使得误差最小。不过,由于这个调整需要考虑很多个点,所以最后的效果是整体误差的缩小,而每个点的误差通常不会精准为0。
最小二乘法有很多方法来求解,比如高斯-牛顿法,列文伯格-马夸尔特法。不过无论使用哪一种方法,我们都需要先计算每个误差项关于优化变量的导数,也就是线性化,使用一阶泰勒展开得:
e(x+△x)≈e(x)+△x
在这里是关键,我们来推导一下
的形式。首先,我们记相机坐标系下的空间点P为
=
。根据相机投影模型,我们可以得到像素坐标:
我们使用左乘扰动模型来解决对优化变量的求导,我们对T左乘扰动量△x,然后考虑e的变化关于扰动量的导数,利用链式法则得:
最终得到的雅克比矩阵描述了重投影误差关于相机位姿李代数的一阶变化关系。然后就可以使用高斯-牛顿法来求位姿的最优解了。
代码实现
下面为具体实现代码,其中包括使用OPENCV中的EPNP,高斯-牛顿法和g2o进行BA优化:
#include <iostream>
#include <opencv2/core/core.hpp>//opencv核心模块
#include <opencv2/features2d/features2d.hpp>//opencv特征点
#include <opencv2/highgui/highgui.hpp>//opencv gui
#include <opencv2/calib3d/calib3d.hpp>//求解器头文件
#include <Eigen/Core>//eigen核心模块
#include <g2o/core/base_vertex.h>//g2o顶点(Vertex)头文件 视觉slam十四讲p141用顶点表示优化变量,用边表示误差项
#include <g2o/core/base_unary_edge.h>//g2o边(edge)头文件
#include <g2o/core/sparse_optimizer.h>//稠密矩阵求解
#include <g2o/core/block_solver.h>//求解器头文件
#include <g2o/core/solver.h>
#include <g2o/core/optimization_algorithm_gauss_newton.h>//高斯牛顿算法头文件
#include <g2o/solvers/dense/linear_solver_dense.h>//线性求解
#include <sophus/se3.hpp>//李群李代数se3
#include <chrono>
using namespace std;
using namespace cv;
void find_feature_matches(
const Mat &img_1, const Mat &img_2,
std::vector<KeyPoint> &keypoints_1,
std::vector<KeyPoint> &keypoints_2,
std::vector<DMatch> &matches);//定义find_feature_matches函数 输入图像1和图像2,输出特征点集合1、特征点集合2和匹配点对
// 像素坐标转相机归一化坐标
Point2d pixel2cam(const Point2d &p, const Mat &K);
// BA by g2o
typedef vector<Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d>> VecVector2d;//2d点 见视觉slam十四讲 p180-p187 需要输入2d点
typedef vector<Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d>> VecVector3d;//3d点 见视觉slam十四讲 p180-p187 需要输入3d点
void bundleAdjustmentG2O(
const VecVector3d &points_3d,
const VecVector2d &points_2d,
const Mat &K,
Sophus::SE3d &pose
); //定义bundleAdjustmentG2O函数 输入3d点和2d点和相机内参矩阵,输出pose为优化变量 使用BA方法
// BA by gauss-newton
void bundleAdjustmentGaussNewton(
const VecVector3d &points_3d,
const VecVector2d &points_2d,
const Mat &K,
Sophus::SE3d &pose
);//定义bundleAdjustmentGaussNewton函数 输入3d点和2d点和相机内参矩阵,输出pose为优化变量 使用高斯牛顿法
int main(int argc, char **argv) {
if (argc != 5) {
cout << "usage: pose_estimation_3d2d img1 img2 depth1 depth2" << endl;//输出命令行用法
return 1;
}
//-- 读取图像
Mat img_1 = imread(argv[1], CV_LOAD_IMAGE_COLOR);//读取图像1 CV_LOAD_IMAGE_COLOR表示返回一张彩色图像
Mat img_2 = imread(argv[2], CV_LOAD_IMAGE_COLOR);//读取图像2 CV_LOAD_IMAGE_COLOR表示返回一张彩色图像
assert(img_1.data && img_2.data && "Can not load images!");//assert()为断言函数,条件为假则停止执行
vector<KeyPoint> keypoints_1, keypoints_2;//特征点1 -> 图像1 特征点2 -> 图像2
vector<DMatch> matches;//匹配 matches
find_feature_matches(img_1, img_2, keypoints_1, keypoints_2, matches);//调用find_feature_matches函数
cout << "一共找到了" << matches.size() << "组匹配点" << endl;//输出匹配点数
//************************调用opencv函数求解pnp******************************
// 建立3D点
Mat d1 = imread(argv[3], CV_LOAD_IMAGE_UNCHANGED); // 深度图为16位无符号数,单通道图像
Mat K = (Mat_<double>(3, 3) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1);//初始化相机内参矩阵
vector<Point3f> pts_3d;//3d路标点
vector<Point2f> pts_2d;//2d像素点
for (DMatch m:matches) {
ushort d = d1.ptr<unsigned short>(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));
pts_2d.push_back(keypoints_2[m.trainIdx].pt);
}
cout << "3d-2d pairs: " << pts_3d.size() << endl;//输出3d-2d pairs
chrono::steady_clock::time_point t1 = chrono::steady_clock::now();//开始计时
Mat r, t;//r表示旋转向量 t表示平移向量
solvePnP(pts_3d, pts_2d, K, Mat(), r, t, false); // 调用OpenCV 的 PnP 求解,可选择EPNP,DLS等方法
Mat R;//旋转矩阵R
cv::Rodrigues(r, R); // r为旋转向量形式,用Rodrigues公式转换为矩阵 视觉slam十四讲p53式3.15
chrono::steady_clock::time_point t2 = chrono::steady_clock::now();//计时结束
chrono::duration<double> time_used = chrono::duration_cast<chrono::duration<double>>(t2 - t1);//计算耗时
cout << "solve pnp in opencv cost time: " << time_used.count() << " seconds." << endl;//输出使用opencv中使用pnp所花费的时间
cout << "R=" << endl << R << endl;//输出旋转矩阵
cout << "t=" << endl << t << endl;//输出平移向量
//*************************使用BA方法*****************************************
VecVector3d pts_3d_eigen;
VecVector2d pts_2d_eigen;
for (size_t i = 0; i < pts_3d.size(); ++i) //遍历3d点
{
pts_3d_eigen.push_back(Eigen::Vector3d(pts_3d[i].x, pts_3d[i].y, pts_3d[i].z));
pts_2d_eigen.push_back(Eigen::Vector2d(pts_2d[i].x, pts_2d[i].y));
}
cout << "calling bundle adjustment by gauss newton" << endl;//输出calling bundle adjustment by gauss newton
Sophus::SE3d pose_gn;
t1 = chrono::steady_clock::now();//计时开始
bundleAdjustmentGaussNewton(pts_3d_eigen, pts_2d_eigen, K, pose_gn);//调用bundleAdjustmentGaussNewton函数
t2 = chrono::steady_clock::now();//计时结束
time_used = chrono::duration_cast<chrono::duration<double>>(t2 - t1);//计时结束
cout << "solve pnp by gauss newton cost time: " << time_used.count() << " seconds." << endl;//输出
cout << "calling bundle adjustment by g2o" << endl;
Sophus::SE3d pose_g2o;
t1 = chrono::steady_clock::now();
bundleAdjustmentG2O(pts_3d_eigen, pts_2d_eigen, K, pose_g2o);
t2 = chrono::steady_clock::now();
time_used = chrono::duration_cast<chrono::duration<double>>(t2 - t1);
cout << "solve pnp by g2o cost time: " << time_used.count() << " seconds." << endl;//输出在G2O中求解pnp耗时
return 0;
}
void find_feature_matches(const Mat &img_1, const Mat &img_2,
std::vector<KeyPoint> &keypoints_1,
std::vector<KeyPoint> &keypoints_2,
std::vector<DMatch> &matches) {
//-- 初始化
Mat descriptors_1, descriptors_2;//描述子和描述子2
// used in OpenCV3
Ptr<FeatureDetector> detector = ORB::create();
Ptr<DescriptorExtractor> descriptor = ORB::create();
// use this if you are in OpenCV2
// Ptr<FeatureDetector> detector = FeatureDetector::create ( "ORB" );
// Ptr<DescriptorExtractor> descriptor = DescriptorExtractor::create ( "ORB" );
Ptr<DescriptorMatcher> matcher = DescriptorMatcher::create("BruteForce-Hamming");//使用汉明距离进行特征匹配
//-- 第一步:检测 Oriented FAST 角点位置
detector->detect(img_1, keypoints_1);
detector->detect(img_2, keypoints_2);
//-- 第二步:根据角点位置计算 BRIEF 描述子
descriptor->compute(img_1, keypoints_1, descriptors_1);//检测图像1的 Oriented FAST 角点
descriptor->compute(img_2, keypoints_2, descriptors_2);//检测图像2的 Oriented FAST 角点
//-- 第三步:对两幅图像中的BRIEF描述子进行匹配,使用 Hamming 距离
vector<DMatch> match;
// BFMatcher matcher ( NORM_HAMMING );
matcher->match(descriptors_1, descriptors_2, match);
//-- 第四步:匹配点对筛选
double min_dist = 10000, max_dist = 0;//求最小距离和最大距离
//找出所有匹配之间的最小距离和最大距离, 即是最相似的和最不相似的两组点之间的距离
for (int i = 0; i < descriptors_1.rows; i++) {
double dist = match[i].distance;
if (dist < min_dist) min_dist = dist;
if (dist > max_dist) max_dist = dist;
}
printf("-- Max dist : %f \n", max_dist);
printf("-- Min dist : %f \n", min_dist);
//当描述子之间的距离大于两倍的最小距离时,即认为匹配有误.但有时候最小距离会非常小,设置一个经验值30作为下限.
//遍历所有匹配,排除误匹配
for (int i = 0; i < descriptors_1.rows; i++) {
if (match[i].distance <= max(2 * min_dist, 30.0))//不同的结果可以在这里设置
//当描述子之间的距离大于两倍的最小距离时,即认为匹配有误 30.0为经验值
{
matches.push_back(match[i]);
}
}
}
Point2d pixel2cam(const Point2d &p, const Mat &K)
{
return Point2d
(
(p.x - K.at<double>(0, 2)) / K.at<double>(0, 0),
(p.y - K.at<double>(1, 2)) / K.at<double>(1, 1)
);
}
void bundleAdjustmentGaussNewton(
const VecVector3d &points_3d,
const VecVector2d &points_2d,
const Mat &K,
Sophus::SE3d &pose) {
typedef Eigen::Matrix<double, 6, 1> Vector6d;//6*1矩阵
const int iterations = 10;//迭代次数设为10
double cost = 0, lastCost = 0;
double fx = K.at<double>(0, 0);//相机内参 具体含义见视觉slam十四讲p99
double fy = K.at<double>(1, 1);//相机内参 具体含义见视觉slam十四讲p99
double cx = K.at<double>(0, 2);//相机内参 具体含义见视觉slam十四讲p99
double cy = K.at<double>(1, 2);//相机内参 具体含义见视觉slam十四讲p99
for (int iter = 0; iter < iterations; iter++)//迭代
{
Eigen::Matrix<double, 6, 6> H = Eigen::Matrix<double, 6, 6>::Zero();//将6*6矩阵初始化为0
Vector6d b = Vector6d::Zero();
cost = 0;//代价函数值置为0
// compute cost
for (int i = 0; i < points_3d.size(); i++)//遍历3d点
//计算增量方程中的H和b以及代价函数值
{
Eigen::Vector3d pc = pose * points_3d[i];//P' = TP =[X',Y',Z'] 视觉slam十四讲p186式7.38
double inv_z = 1.0 / pc[2];//相当于1 / Z'
double inv_z2 = inv_z * inv_z;//相当于( 1 / Z' ) * ( 1 / Z' )
Eigen::Vector2d proj(fx * pc[0] / pc[2] + cx, fy * pc[1] / pc[2] + cy);//u = fx(X' / z') +cx,v = fy(Y' / z') +cy 视觉slam十四讲p186式7.41
Eigen::Vector2d e = points_2d[i] - proj;
cost += e.squaredNorm();
Eigen::Matrix<double, 2, 6> J;//2*6雅克比矩阵 视觉slam十四讲p186式7.46
//雅克比矩阵表达式见 视觉slam十四讲p186式7.46
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;
}
// -fx * inv_z 相当于-fx / Z'
//0
//fx * pc[0] * inv_z2相当于fx * X' / ( Z' * Z' )
//-fx - fx * pc[0] * pc[0] * inv_z2相当于fx * X' * Y' / ( Z' * Z')
//fx * pc[1] * inv_z相当于fx * Y' / Z'
//0
//-fy * inv_z相当于-fy / Z'
//fy * pc[1] * inv_z2相当于fy * Y' / (Z' * Z')
//fy + fy * pc[1] * pc[1] * inv_z2相当于fy + fy * Y'*Y' / (Z' * Z')
//-fy * pc[0] * pc[1] * inv_z2相当于fy * X' * Y' / ( Z' * Z')
//-fy * pc[0] * inv_z相当于-fy * X' / Z'
Vector6d dx;
dx = H.ldlt().solve(b);//LDT求解
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;
}
// update your estimation
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;//输出pose by g-n
}
/// vertex and edges used in g2o ba
// 曲线模型的顶点,模板参数:优化变量维度和数据类型
class VertexPose : public g2o::BaseVertex<6, Sophus::SE3d>//:表示继承,public表示公有继承;CurveFittingVertex是派生类,:BaseVertex<6, Sophus::SE3d>是基类
{
public://以下定义的成员变量和成员函数都是公有的
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;//解决Eigen库数据结构内存对齐问题
// 重置
virtual void setToOriginImpl() override //virtual表示该函数为虚函数,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 {}//istream类是c++标准输入流的一个基类
//可参照C++ Primer Plus第六版的6.8节
virtual bool write(ostream &out) const override {}//ostream类是c++标准输出流的一个基类
//可参照C++ Primer Plus第六版的6.8节
};
// 误差模型 模板参数:观测值维度,类型,连接顶点类型
class EdgeProjection : public g2o::BaseUnaryEdge<2, Eigen::Vector2d, VertexPose> {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;//解决Eigen库数据结构内存对齐问题
EdgeProjection(const Eigen::Vector3d &pos, const Eigen::Matrix3d &K) : _pos3d(pos), _K(K) {}//使用列表赋初值
virtual void computeError() override//virtual表示虚函数,保留字override表示当前函数重写了基类的虚函数
{
const VertexPose *v = static_cast<VertexPose *> (_vertices[0]);//创建指针v
Sophus::SE3d T = v->estimate();//将estimate()值赋给V
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<VertexPose *> (_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;
} //雅克比矩阵表达式见 视觉slam十四讲p186式7.46
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
typedef g2o::BlockSolver<g2o::BlockSolverTraits<6, 3>> BlockSolverType; // pose is 6, landmark is 3
typedef g2o::LinearSolverDense<BlockSolverType::PoseMatrixType> LinearSolverType; // 线性求解器类型
// 梯度下降方法,可以从GN, LM, DogLeg 中选
auto solver = new g2o::OptimizationAlgorithmGaussNewton(
g2o::make_unique<BlockSolverType>(g2o::make_unique<LinearSolverType>()));//c++中的make_unique表示智能指针类型
g2o::SparseOptimizer optimizer; // 图模型
optimizer.setAlgorithm(solver); // 设置求解器
optimizer.setVerbose(true); // 打开调试输出
// vertex
// 往图中增加顶点
VertexPose *vertex_pose = new VertexPose(); // camera vertex_pose
vertex_pose->setId(0);//对顶点进行编号,里面的0你可以写成任意的正整数,但是后面设置edge连接顶点时,必须要和这个一致
vertex_pose->setEstimate(Sophus::SE3d());
optimizer.addVertex(vertex_pose);//添加顶点
// K 相机内参矩阵
Eigen::Matrix3d K_eigen;
K_eigen <<
K.at<double>(0, 0), K.at<double>(0, 1), K.at<double>(0, 2),
K.at<double>(1, 0), K.at<double>(1, 1), K.at<double>(1, 2),
K.at<double>(2, 0), K.at<double>(2, 1), K.at<double>(2, 2);
// edges
// 往图中增加边
int index = 1;
for (size_t i = 0; i < points_2d.size(); ++i)//遍历2d点
{
auto p2d = points_2d[i];
auto p3d = points_3d[i];
EdgeProjection *edge = new EdgeProjection(p3d, K_eigen);
edge->setId(index);//对顶点进行编号,里面的0你可以写成任意的正整数,但是后面设置edge连接顶点时,必须要和这个一致
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);//迭代次数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 << "pose estimated by g2o =\n" << vertex_pose->estimate().matrix() << endl;
pose = vertex_pose->estimate();
}