SLAM中的位姿概念对新手很难,这里讨论下。首先放出一张图,下文会反复说道这张图。
注意到位姿节点之间的变换并不是位姿,之前一直有误解;一般地有如下概念:
路标节点:也就是观测方程【数学形式下见】的观测值,也就是特征点的像素坐标[u,v],或者该帧相机坐标系下的3d坐标[x,y,z];
位姿节点:也就是运动方程【数学形式下见】的输出值。例如:上图x1、x2、x3、X4对应位姿为:Tcw1、Tcw2、Tcw3、Tcw4。这里的Tcw表示对应帧相机坐标系->世界坐标系的变换;比如:在x1处看到了路标点p1,在x2处也看到了路标点p1(当然是通过特征匹配才知道再次看到)考虑以下两种情况:
1> x1对应第一帧,x2对应第二帧
那么x1的相机坐标系即为:世界坐标系;那么第一帧位姿我们直接初始化为:
第二帧我们要:通过opencv中solvePNPransac(points3d_1, points2d_2,R,t);来求解,points3d_1对应的是世界坐标系下的3D点(在这种情形,第一帧相机坐标系也就是世界坐标系,所以第一帧相机坐标系下的3D点), points2d_2是第二帧像素点(设第二帧对应3D路标点(在第二帧相机坐标系下)为:points3d_2)。
在这里[左乘]:
Tcw2 * points3d_1 = points3d_2
同时必须知道:(假设两帧之间的变换 T12,也就是 位姿变换):
T12 * Tcw1 = Tcw2
2> x2对应第2帧,x3对应第3帧
接着,我们再次想通过solvePNPransac(points3d_2_, points2d_3,R,t)来求解Tcw3,points3d_2_ (世界坐标系)肯定不是 points3d_2(相机坐标系),所以在第一种情形你就应该提前将points3d_2 从它所在的相机坐标系映射到世界坐标系,故:
points3d_2_ = Tcw2.inverse() * points3d_2
我们得出流程图如下图(多年前VISO画的):
观测模型:具体见下
运动模型:具体见下
两个模型与G2O结合了解说明;
位姿,即:位置和姿态,位置对应位移,姿态对应旋转。
对于上述位姿图,我们假设 x1 对应参考帧 ref_(同时假设是第一帧),x2对应 当前帧curr_(同时假设是第二帧);我们通过......最后通过opencv中API solvePNPransac();求出的R|t 其实是Tcw;
- Tcw指的是:当前帧与世界坐标系之间的变换;
- Trw指的是:参考帧与世界坐标系之间的变换。那么待估计的两帧之间的变换为:Tcr,构成左乘关系:
Tcr, s.t. Tcr * Trw = Tcw
- P_camera_curr 指的是:当前帧3D路标点 (相机坐标系)
- P_world_ref 指的是:参考帧3D路标点 (世界坐标系)
P_camera_curr = Tcw*P_world_ref
这里 opencv中的 solvePNPransac 求出来的是 T = (R|t);依据上述公式:所以你要将当前帧3D路标点转化到世界坐标系,应该是左乘:Tcw.inverse() * P_camera_curr = P_world_ref;请看以下代码【就是匹配,第一帧相机坐标系当作世界坐标系,第二帧就是相机坐标系,重点关注代码 81行 - 124行】:
(代码依赖opencv和g2o)
#include <iostream>
#include <opencv2/core/core.hpp>
#include <opencv2/features2d/features2d.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/calib3d/calib3d.hpp>
#include <Eigen/Core>
#include <Eigen/Geometry>
#include <g2o/core/base_vertex.h>
#include <g2o/core/base_unary_edge.h>
#include <g2o/core/block_solver.h>
#include <g2o/core/optimization_algorithm_levenberg.h>
#include <g2o/solvers/csparse/linear_solver_csparse.h>
#include <g2o/types/sba/types_six_dof_expmap.h>
#include <chrono>
using namespace std;
using namespace cv;
#include"sophus\se3.h"
#include"sophus\so3.h"
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);
// 像素坐标转相机归一化坐标
Point2d pixel2cam(const Point2d& p, const Mat& K);
void bundleAdjustment(
const vector<Point3f> points_3d,
const vector<Point2f> points_2d,
const Mat& K,
Mat& R, Mat& t
);
int main()
{
//-- 读取图像
Mat img_1 = imread("color/b.png", CV_LOAD_IMAGE_COLOR);
Mat img_2 = imread("color/c.png", CV_LOAD_IMAGE_COLOR);
vector<KeyPoint> keypoints_1, keypoints_2;
vector<DMatch> matches;
find_feature_matches(img_1, img_2, keypoints_1, keypoints_2, matches);
cout << "一共找到了" << matches.size() << "组匹配点" << endl;
// 建立3D点
Mat depth_1 = imread("depth/b.pgm", CV_LOAD_IMAGE_UNCHANGED); // 深度图为16位无符号数,单通道图像
Mat depth_2 = imread("depth/c.pgm", CV_LOAD_IMAGE_UNCHANGED); // 深度图为16位无符号数,单通道图像
//Mat K = (Mat_<double>(3, 3) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1);
Mat K = (Mat_<double>(3, 3) << 518.0, 0, 325.5, 0, 519.0, 253.5, 0, 0, 1);
vector<Point3f> pts_3d1;//世界坐标点
vector<Point3f> pts_3d2;
vector<Point2f> pts_2d;//相机坐标系点(归一化???)
//【注:】这里表示同一个3D点在两幅图中的图二对应像素点,本来就是求世界坐标系下的r、t
for (DMatch m : matches)
{
//取出深度值,此时彩图和深度图已经对齐
ushort d1 = depth_1.ptr<unsigned short>(int(keypoints_1[m.queryIdx].pt.y))[int(keypoints_1[m.queryIdx].pt.x)];
ushort d2 = depth_2.ptr<unsigned short>(int(keypoints_2[m.trainIdx].pt.y))[int(keypoints_2[m.trainIdx].pt.x)];
if ((d1 == 0) || (d2 == 0)) // bad depth
continue;
float dd1 = d1 / 1.0;
float dd2 = d2 / 1.0;
Point2d p1 = pixel2cam(keypoints_1[m.queryIdx].pt, K); // 相机坐标系归一化平面:p1的形式 [x/z,y/z,1]
Point2d p2 = pixel2cam(keypoints_2[m.trainIdx].pt, K);
pts_3d1.push_back(Point3f(p1.x*dd1, p1.y*dd1, dd1));//乘以Z就得到形式 [x,y,z]?????左边相机为参考,把他当作世界坐标系,确实是这样的
pts_3d2.push_back(Point3f(p2.x*dd2, p2.y*dd2, dd2));
pts_2d.push_back(keypoints_2[m.trainIdx].pt);//图二中的2D像素坐标[u,v]
}
cout << "3d-2d pairs: " << pts_3d1.size() << endl;
Mat r, t;
// 调用OpenCV 的 PnP 求解r t,可选择EPNP,DLS等方法
//solvePnP(pts_3d, pts_2d, K, Mat(), r, t, false);
//solvePnP(pts_3d1, pts_2d, K, Mat(), r, t, false, SOLVEPNP_EPNP);
cv::solvePnPRansac(pts_3d1, pts_2d, K, Mat(), r, t, false, 100, 1.0, 0.99);
Mat R;
cv::Rodrigues(r, R); // r为旋转向量形式,用Rodrigues公式转换为矩阵
//RR = -R.inv();
cout << "R=" << endl << R << endl;
cout << "t=" << endl << t << endl;
//************************************************************************************************
// 李群
//************************************************************************************************
Sophus::SE3 T_se3 = Sophus::SE3(
Sophus::SO3(r.at<double>(0, 0), r.at<double>(1, 0), r.at<double>(2, 0)),
Sophus::Vector3d(t.at<double>(0, 0), t.at<double>(1, 0), t.at<double>(2, 0))
);
cout << "T_se3 = " << T_se3.matrix() << endl;
//************************************************************************************************
// 欧氏群
//************************************************************************************************
Eigen::Isometry3d T_Isometry3d = Eigen::Isometry3d::Identity();
//Eigen::AngleAxisd rot_vec(r.at<double>(0, 0), r.at<double>(1, 0), r.at<double>(2, 0));
Eigen::Vector3d trans(t.at<double>(0, 0), t.at<double>(1, 0), t.at<double>(2, 0));
Eigen::Matrix<double, 3, 3> R_;
R_ << R.at<double>(0,0), R.at<double>(0,1), R.at<double>(0,2),
R.at<double>(1,0), R.at<double>(1,1), R.at<double>(1,2),
R.at<double>(2,0), R.at<double>(2,1), R.at<double>(2,2);
T_Isometry3d.rotate(R_);
T_Isometry3d.pretranslate(trans);
cout << " T_Isometry3d = " << T_Isometry3d.matrix() << endl;
cout << "calling bundle adjustment" << endl;
bundleAdjustment(pts_3d1, pts_2d, K, R, t);
//************************************************************************************************
// 计算误差:error = point3d_curr -( R * point3d_ref + t )
//************************************************************************************************
for (int i = 0; i < 20; i++)
{
cout << " pts_3d1 = " << pts_3d1[i] << endl;
cout << " pts_3d2 = " << pts_3d2[i] << endl;
cout << " error " <<
(Mat_<double>(3, 1) << pts_3d2[i].x, pts_3d2[i].y, pts_3d2[i].z)
- R*((Mat_<double>(3, 1) << pts_3d1[i].x, pts_3d1[i].y, pts_3d1[i].z)) - t
<< endl;
cout << endl;
}
waitKey(0);
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;
// used in OpenCV3
Ptr<FeatureDetector> detector = ORB::create(1000);
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);
descriptor->compute(img_2, keypoints_2, descriptors_2);
//-- 第三步:对两幅图像中的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))
{
matches.push_back(match[i]);
}
}
Mat img_match;
Mat img_goodmatch;
drawMatches(img_1, keypoints_1, img_2, keypoints_2, match, img_match);
drawMatches(img_1, keypoints_1, img_2, keypoints_2, matches, img_goodmatch);
namedWindow("所有匹配点对", CV_WINDOW_NORMAL);
imshow("所有匹配点对", img_match);
namedWindow("优化后匹配点对", CV_WINDOW_NORMAL);
imshow("优化后匹配点对", img_goodmatch);
}
Point2d pixel2cam(const Point2d& p, const Mat& K)// [u,v,1] - > [x/z, y/z, 1]
{
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 bundleAdjustment(
const vector< Point3f > points_3d,
const vector< Point2f > points_2d,
const Mat& K,
Mat& R, Mat& t)
{
// 初始化g2o
typedef g2o::BlockSolver< g2o::BlockSolverTraits<6, 3> > Block; // pose 维度为 6, landmark 维度为 3
Block::LinearSolverType* linearSolver = new g2o::LinearSolverCSparse<Block::PoseMatrixType>(); // 线性方程求解器
Block* solver_ptr = new Block(linearSolver); // 矩阵块求解器
g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr);
g2o::SparseOptimizer optimizer;
optimizer.setAlgorithm(solver);
// vertex
g2o::VertexSE3Expmap* pose = new g2o::VertexSE3Expmap(); // camera pose
Eigen::Matrix3d R_mat;
R_mat <<
R.at<double>(0, 0), R.at<double>(0, 1), R.at<double>(0, 2),
R.at<double>(1, 0), R.at<double>(1, 1), R.at<double>(1, 2),
R.at<double>(2, 0), R.at<double>(2, 1), R.at<double>(2, 2);
pose->setId(0);
pose->setEstimate(g2o::SE3Quat(
R_mat,
Eigen::Vector3d(t.at<double>(0, 0), t.at<double>(1, 0), t.at<double>(2, 0))
));
optimizer.addVertex(pose);
int index = 1;
for (const Point3f p : points_3d) // landmarks
{
g2o::VertexSBAPointXYZ* point = new g2o::VertexSBAPointXYZ();
point->setId(index++);
point->setEstimate(Eigen::Vector3d(p.x, p.y, p.z));
point->setMarginalized(true); // g2o 中必须设置 marg 参见第十讲内容
optimizer.addVertex(point);
}
// parameter: camera intrinsics
g2o::CameraParameters* camera = new g2o::CameraParameters(
K.at<double>(0, 0), Eigen::Vector2d(K.at<double>(0, 2), K.at<double>(1, 2)), 0
);
camera->setId(0);
optimizer.addParameter(camera);
// edges
index = 1;
for (const Point2f p : points_2d)
{
g2o::EdgeProjectXYZ2UV* edge = new g2o::EdgeProjectXYZ2UV();
edge->setId(index);
edge->setVertex(0, dynamic_cast<g2o::VertexSBAPointXYZ*> (optimizer.vertex(index)));
edge->setVertex(1, pose);
edge->setMeasurement(Eigen::Vector2d(p.x, p.y));
edge->setParameterId(0, 0);
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(100);
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=" << endl << Eigen::Isometry3d(pose->estimate()).matrix() << endl;
}
这里我们只关心运动,不关心结构。换句话说,只要通过特征点成功求出了运动,我们就不再需要这帧的特征点了。这种做法当然会有缺陷,但是忽略掉数量庞大的特征点可以节省许多的计算量。然后,在 t 到 t + 1 时刻,我们又以 t 时刻为参考帧,考虑 t 到 t + 1 间的运动关系。如此往复,就得到了一条运动轨迹。