7.2 实践:特征提取和匹配

(1)环境搭建

下面所有代码基于opencv2.4实现 opencv2安装方法:​​当然也可以搭建opencv3的环境,但代码需要做一定的修改

(2)代码详解

#include <iostream>
#include <opencv2/core/core.hpp>
#include <opencv2/features2d/features2d.hpp>
#include <opencv2/highgui/highgui.hpp>

using namespace std;
using namespace cv;

int main (int argc, char** argv)
{
if (argc != 3){
cout << "usage: feature_extraction img1 img2" << endl;
return 1;
}

//-- 读取图像
Mat img_1 = imread(argv[1], CV_LOAD_IMAGE_COLOR);
Mat img_2 = imread(argv[2], CV_LOAD_IMAGE_COLOR);

//-- 初始化
std::vector<KeyPoint> keypoints_1, keypoints_2; //关键点
Mat descriptors_1, descriptors_2; //描述子
//opencv3 use this
//Ptr<FeatureDetector> detector = ORB::create();
//Ptr<DescriptorExtractor> descriptor = ORB::create();
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);

//绘带有特征点的图
Mat outimg1;
drawKeypoints(img_1, keypoints_1, outimg1, Scalar::all(-1), DrawMatchesFlags::DEFAULT);
imshow("ORB特征点", outimg1);


//-- 第三步:对两幅图像中的BRIEF描述子进行匹配,使用 Hamming 距离
vector<DMatch> matches;
//BFMatcher matcher ( NORM_HAMMING );
matcher->match(descriptors_1, descriptors_2, matches);

//-- 第四步:匹配点对筛选
double min_dist=10000, max_dist=0;
//找出所有匹配之间的最小距离和最大距离, 即是最相似的和最不相似的两组点之间的距离
for (int i = 0; i < descriptors_1.rows; i++){
double dist = matches[i].distance;
if (dist < min_dist) min_dist = dist;
if (dist > max_dist) max_dist = dist;
}
// 仅供娱乐的写法
//min_dist = min_element( matches.begin(), matches.end(), [](const DMatch& m1, const DMatch& m2) {return m1.distance<m2.distance;} )->distance;
//max_dist = max_element( matches.begin(), matches.end(), [](const DMatch& m1, const DMatch& m2) {return m1.distance<m2.distance;} )->distance;
printf("-- Max dist : %f \n", max_dist);
printf("-- Min dist : %f \n", min_dist);

//当描述子之间的距离大于两倍的最小距离时,即认为匹配有误.但有时候最小距离会非常小,设置一个经验值30作为下限.
std::vector< DMatch > good_matches;
for (int i = 0; i < descriptors_1.rows; i++){
if (matches[i].distance <= max(2*min_dist, 30.0)){
good_matches.push_back(matches[i]);
}
}


//-- 第五步:绘制匹配结果
Mat img_match;
Mat img_goodmatch;
drawMatches(img_1, keypoints_1, img_2, keypoints_2, matches, img_match);
drawMatches(img_1, keypoints_1, img_2, keypoints_2, good_matches, img_goodmatch);
imshow("所有匹配点对", img_match);
imshow("优化后匹配点对", img_goodmatch);
waitKey(0);

return 0;
}

CMakeLists.txt

cmake_minimum_required( VERSION 2.8 )
project( feature_extraction )

# 添加c++ 11标准支持
set( CMAKE_CXX_FLAGS "-std=c++11" )

# 寻找OpenCV库
find_package( OpenCV REQUIRED ) #这里我去掉了3,因为我的版本是2
# 添加头文件
include_directories( ${OpenCV_INCLUDE_DIRS} )

add_executable( feature_extraction feature_extraction.cpp )
# 链接OpenCV库
target_link_libraries( feature_extraction ${OpenCV_LIBS} )


(3)编译

第7讲 视觉里程计1_3d

mkdir build
cd build
cmake ..
make
cd ..
build/feature_extarction 1.png 2.png


7.4 实践:对极约束求解相机运动

(1)环境搭建

opencv2.4

(2)2d2d代码详解

pose_estimation_2d2d.cpp

#include <iostream>
#include <opencv2/core/core.hpp>
#include <opencv2/features2d/features2d.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/calib3d/calib3d.hpp>
#include "extra.h" // use this if in OpenCV2
using namespace std;
using namespace cv;

/****************************************************
* 本程序演示了如何使用2D-2D的特征匹配估计相机运动
* **************************************************/

//函数声明
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 );

void pose_estimation_2d2d(
std::vector<KeyPoint> keypoints_1,
std::vector<KeyPoint> keypoints_2,
std::vector< DMatch > matches,
Mat& R, Mat& t );

// 像素坐标转相机归一化坐标
Point2d pixel2cam (const Point2d& p, const Mat& K);


int main (int argc, char** argv)
{
if (argc != 3){
cout << "usage: pose_estimation_2d2d img1 img2" << endl;
return 1;
}

// 1.读取图像
Mat img_1 = imread(argv[1], CV_LOAD_IMAGE_COLOR);
Mat img_2 = imread(argv[2], CV_LOAD_IMAGE_COLOR);

// 2.特征匹配
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;

// 3.估计两张图像间运动
Mat R,t;
pose_estimation_2d2d(keypoints_1, keypoints_2, matches, R, t);

//-- 验证E=t^R*scale
Mat t_x = (Mat_<double> (3,3) <<
0, -t.at<double> (2,0), t.at<double> (1,0),
t.at<double> (2,0), 0, -t.at<double> (0,0),
-t.at<double> (1,0), t.at<double> (0,0), 0);

cout << "t^R=" << endl << t_x*R << endl; //本质矩阵E

//-- 验证对极约束
Mat K = (Mat_<double> (3,3) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1);
for (DMatch m : matches) {
Point2d pt1 = pixel2cam(keypoints_1[m.queryIdx].pt, K);
Mat y1 = (Mat_<double> (3,1) << pt1.x, pt1.y, 1);
Point2d pt2 = pixel2cam(keypoints_2[m.trainIdx].pt, K);
Mat y2 = (Mat_<double> (3,1) << pt2.x, pt2.y, 1);
Mat d = y2.t() * t_x * R * y1;
cout << "epipolar constraint = " << d << endl;
}
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;
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]);
}
}
}



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 pose_estimation_2d2d ( std::vector<KeyPoint> keypoints_1,
std::vector<KeyPoint> keypoints_2,
std::vector< DMatch > matches,
Mat& R, Mat& t ) {
// 相机内参,TUM Freiburg2
Mat K = (Mat_<double> (3,3) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1);

//-- 把匹配点转换为vector<Point2f>的形式
vector<Point2f> points1;
vector<Point2f> points2;
for (int i = 0; i < (int) matches.size(); i++){
points1.push_back(keypoints_1[matches[i].queryIdx].pt);
points2.push_back(keypoints_2[matches[i].trainIdx].pt);
}

// 1.计算基础矩阵F
Mat fundamental_matrix = findFundamentalMat(points1, points2, CV_FM_8POINT);
cout << "fundamental_matrix is: " << endl << fundamental_matrix << endl;

// 2.计算本质矩阵E
Point2d principal_point (325.1, 249.7); //相机光心, TUM dataset标定值
double focal_length = 521; //相机焦距, TUM dataset标定值
Mat essential_matrix =
findEssentialMat(points1, points2, focal_length, principal_point);
cout << endl << "essential_matrix is: " << endl << essential_matrix << endl;

// 3.计算单应矩阵H
Mat homography_matrix = findHomography(points1, points2, RANSAC, 3);
cout << endl << "homography_matrix is: " << endl<< homography_matrix << endl;

// 4.从本质矩阵中恢复旋转和平移信息.
recoverPose(essential_matrix, points1, points2, R, t, focal_length, principal_point);
cout << endl << "R is: " << endl << R << endl;
cout << endl << "t is: " << endl << t << endl;

}

CMakeLists.txt

cmake_minimum_required( VERSION 2.8 )
project( pose_estimation_2d2d )

# 添加c++ 11标准支持
set( CMAKE_CXX_FLAGS "-std=c++11" )

# 寻找OpenCV库
find_package( OpenCV REQUIRED ) #这里我去掉了3,因为我的版本是2
# 添加头文件
include_directories( ${OpenCV_INCLUDE_DIRS} )

add_library(extra SHARED extra.cpp)
add_executable( pose_estimation_2d2d pose_estimation_2d2d.cpp )
# 链接OpenCV库
target_link_libraries( pose_estimation_2d2d ${OpenCV_LIBS} extra)


(3)编译

第7讲 视觉里程计1_人工智能_02

mkdir build
cd build
cmake ..
make
cd
build/pose_estimation_2dd 1.png 2.png


7.6 实践:三角测量

(1)环境

opencv2.4

(2)代码详解

triangulation.cpp

#include <iostream>
#include <opencv2/core/core.hpp>
#include <opencv2/features2d/features2d.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/calib3d/calib3d.hpp>
#include "extra.h" // used in opencv2
using namespace std;
using namespace cv;

// 相机内参,TUM Freiburg2
Mat K = (Mat_<double> (3,3) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1);

//函数声明
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 );

void pose_estimation_2d2d (
const std::vector<KeyPoint>& keypoints_1,
const std::vector<KeyPoint>& keypoints_2,
const std::vector< DMatch >& matches,
Mat& R, Mat& t );

void triangulation (
const vector<KeyPoint>& keypoint_1,
const vector<KeyPoint>& keypoint_2,
const std::vector< DMatch >& matches,
const Mat& R, const Mat& t,
vector<Point3d>& points
);

// 像素坐标转相机归一化坐标
Point2f pixel2cam( const Point2d& p, const Mat& K );



int main (int argc, char** argv)
{
if (argc != 3){
cout << "usage: triangulation img1 img2" << endl;
return 1;
}

// 1.读取图像
Mat img_1 = imread(argv[1], CV_LOAD_IMAGE_COLOR);
Mat img_2 = imread(argv[2], CV_LOAD_IMAGE_COLOR);

// 2.特征匹配
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 << endl;

// 3.估计两张图像间运动
Mat R,t;
pose_estimation_2d2d(keypoints_1, keypoints_2, matches, R, t);

// 4.三角化
vector<Point3d> points; //三角测量的输出
triangulation(keypoints_1, keypoints_2, matches, R, t, points);

//-- 验证三角化点与特征点的重投影关系
for (int i = 0; i < matches.size(); i++){
Point2d pt1_cam = pixel2cam(keypoints_1[matches[i].queryIdx].pt, K);
Point2d pt1_cam_3d(points[i].x/points[i].z, points[i].y/points[i].z);

cout << "point in the first camera frame: " << pt1_cam << endl;
cout <<"point projected from 3D "<<pt1_cam_3d<<", d="<<points[i].z<<endl;

// 第二个图
Point2f pt2_cam = pixel2cam(keypoints_2[matches[i].trainIdx].pt, K);
Mat pt2_trans =
R * (Mat_<double>(3,1) << points[i].x, points[i].y, points[i].z) + t;
pt2_trans /= pt2_trans.at<double>(2,0);
cout << "point in the second camera frame: " << pt2_cam << endl;
cout << "point reprojected from second frame: " << pt2_trans.t() << endl;
cout << endl;
}

return 0;
}



//1.特征匹配函数
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();
//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]);
}
}
}


//2.对极约束函数
void pose_estimation_2d2d (
const std::vector<KeyPoint>& keypoints_1,
const std::vector<KeyPoint>& keypoints_2,
const std::vector< DMatch >& matches,
Mat& R, Mat& t ){

//-- 把匹配点转换为vector<Point2f>的形式
vector<Point2f> points1;
vector<Point2f> points2;

for (int i = 0; i < (int) matches.size(); i++){
points1.push_back(keypoints_1[matches[i].queryIdx].pt);
points2.push_back(keypoints_2[matches[i].trainIdx].pt);
}

//-- 计算本质矩阵
Point2d principal_point ( 325.1, 249.7 ); //相机主点, TUM dataset标定值
int focal_length = 521; //相机焦距, TUM dataset标定值
Mat essential_matrix =
findEssentialMat (points1, points2, focal_length, principal_point);
cout << "essential_matrix is " << endl << essential_matrix<<endl;

//-- 从本质矩阵中恢复旋转和平移信息.
recoverPose (essential_matrix, points1, points2, R, t, focal_length, principal_point);
cout << "R is " << endl << R << endl;
cout << "t is " << endl << t << endl;
}



//3.三角测量函数
void triangulation (
const vector<KeyPoint>& keypoint_1,
const vector<KeyPoint>& keypoint_2,
const vector<DMatch>& matches,
const Mat& R, const Mat& t,
vector<Point3d>& points) {
Mat T1 = (Mat_<float> (3,4) <<
1,0,0,0,
0,1,0,0,
0,0,1,0);
Mat T2 = (Mat_<float> (3,4) <<
R.at<double>(0,0), R.at<double>(0,1), R.at<double>(0,2), t.at<double>(0,0),
R.at<double>(1,0), R.at<double>(1,1), R.at<double>(1,2), t.at<double>(1,0),
R.at<double>(2,0), R.at<double>(2,1), R.at<double>(2,2), t.at<double>(2,0)
);

vector<Point2f> pts_1, pts_2;
for (DMatch m : matches){
// 将像素坐标转换至相机坐标
pts_1.push_back(pixel2cam(keypoint_1[m.queryIdx].pt, K));
pts_2.push_back(pixel2cam(keypoint_2[m.trainIdx].pt, K));
}

Mat pts_4d;
cv::triangulatePoints(T1, T2, pts_1, pts_2, pts_4d);

// 转换成非齐次坐标
for (int i = 0; i < pts_4d.cols; i++){
Mat x = pts_4d.col(i);
x /= x.at<float>(3,0); // 归一化
Point3d p(x.at<float>(0,0), x.at<float>(1,0), x.at<float>(2,0));
points.push_back(p);
}
}



Point2f pixel2cam(const Point2d& p, const Mat& K){
return Point2f
(
(p.x - K.at<double>(0,2)) / K.at<double>(0,0),
(p.y - K.at<double>(1,2)) / K.at<double>(1,1)
);
}

CMakeLists.txt

cmake_minimum_required( VERSION 2.8 )
project( triangulation )

# 添加c++ 11标准支持
set( CMAKE_CXX_FLAGS "-std=c++11" )

# 寻找OpenCV库
find_package( OpenCV REQUIRED ) #这里我去掉了3,因为我的版本是2
# 添加头文件
include_directories( ${OpenCV_INCLUDE_DIRS} )

add_library(extra SHARED extra.cpp)
add_executable( triangulation triangulation.cpp )
# 链接OpenCV库
target_link_libraries( triangulation ${OpenCV_LIBS} extra)

(3)编译

第7讲 视觉里程计1_3d_03

mkdir build
cd build
cmake ..
make
build/triangulation.cpp 1.png 2.png

7.8 实践:求解PnP

(1)环境

opencv2.4,g2o

(2)代码详解

CMakeLists.txt

cmake_minimum_required( VERSION 2.8 )
project( pose_estimation_3d2d )

# 添加c++ 11标准支持
set( CMAKE_CXX_FLAGS "-std=c++11" )
set( CMAKE_BUILD_TYPE "Release" )


# 添加cmake模块以使用g2o
list( APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules )

# 寻找OpenCV库
find_package( OpenCV REQUIRED ) #这里我去掉了3,因为我的版本是2
find_package( G2O REQUIRED )
find_package( CSparse REQUIRED )


# 添加头文件
include_directories(
${OpenCV_INCLUDE_DIRS}
${G2O_INCLUDE_DIRS}
${CSPARSE_INCLUDE_DIR}
"/usr/include/eigen3/"
)


add_executable( pose_estimation_3d2d pose_estimation_3d2d.cpp )
# 链接OpenCV库
target_link_libraries( pose_estimation_3d2d
${OpenCV_LIBS}
${CSPARSE_LIBRARY}
g2o_core g2o_stuff g2o_types_sba g2o_csparse_extension
)

pose_estimation_3d2d.cpp

#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;

//函数声明
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 (int argc, char** argv)
{
if (argc != 5) {
cout << "usage: pose_estimation_3d2d img1 img2 depth1 depth2" << endl;
return 1;
}

//1.读取图像
Mat img_1 = imread(argv[1], CV_LOAD_IMAGE_COLOR);
Mat img_2 = imread(argv[2], CV_LOAD_IMAGE_COLOR);

//2.特征匹配
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 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;
vector<Point2f> pts_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) continue; // bad depth

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;

Mat r, t;
solvePnP(pts_3d, pts_2d, K, Mat(), r, t, false); // 调用OpenCV 的 PnP 求解,可选择EPNP,DLS等方法
Mat R;
cv::Rodrigues(r, R); // r为旋转向量形式,用Rodrigues公式转换为矩阵

cout << "R=" << endl << R << endl;
cout << "t=" << endl << t << endl;

//BA优化,使用前一步估计值作为初始值
cout << endl << "calling bundle adjustment" << endl;
bundleAdjustment (pts_3d, pts_2d, K, R, t);
}



//1.特征匹配函数
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();
//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] );
}
}
}



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 )
);
}



//BA函数
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;
}

(3)编译

mkdir build
cd build
cmake ..
make
cd ..
build/pose_estimation_3d2d 1.png 1_depth.png 2.png 2_depth.png

7.10 实践:求解ICP

(1)代码讲解

CMakeLists.txt

cmake_minimum_required( VERSION 2.8 )
project( pose_estimation_3d3d )

# 添加c++ 11标准支持
set( CMAKE_CXX_FLAGS "-std=c++11" )
set( CMAKE_BUILD_TYPE "Release" )


# 添加cmake模块以使用g2o
list( APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules )

# 寻找OpenCV库
find_package( OpenCV REQUIRED ) #这里我去掉了3,因为我的版本是2
find_package( G2O REQUIRED )
find_package( CSparse REQUIRED )


# 添加头文件
include_directories(
${OpenCV_INCLUDE_DIRS}
${G2O_INCLUDE_DIRS}
${CSPARSE_INCLUDE_DIR}
"/usr/include/eigen3/"
)


add_executable( pose_estimation_3d3d pose_estimation_3d3d.cpp )

# 链接OpenCV库
target_link_libraries( pose_estimation_3d3d
${OpenCV_LIBS}
${CSPARSE_LIBRARY}
g2o_core g2o_stuff g2o_types_sba g2o_csparse_extension
)

pose_estimation_3d3d.cpp

#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 <Eigen/SVD>
#include <g2o/core/base_vertex.h>
#include <g2o/core/base_unary_edge.h>
#include <g2o/core/block_solver.h>
#include <g2o/core/optimization_algorithm_gauss_newton.h>
#include <g2o/solvers/eigen/linear_solver_eigen.h>
#include <g2o/types/sba/types_six_dof_expmap.h>
#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 );

// 像素坐标转相机归一化坐标
Point2d pixel2cam ( const Point2d& p, const Mat& K );

void pose_estimation_3d3d (
const vector<Point3f>& pts1,
const vector<Point3f>& pts2,
Mat& R, Mat& t
);

void bundleAdjustment(
const vector<Point3f>& points_3d,
const vector<Point3f>& points_2d,
Mat& R, Mat& t
);



// g2o edge
class EdgeProjectXYZRGBDPoseOnly : public g2o::BaseUnaryEdge<3, Eigen::Vector3d, g2o::VertexSE3Expmap> {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
EdgeProjectXYZRGBDPoseOnly( const Eigen::Vector3d& point ) : _point(point) {}

virtual void computeError()
{
const g2o::VertexSE3Expmap* pose = static_cast<const g2o::VertexSE3Expmap*> ( _vertices[0] );
// measurement is p, point is p'
_error = _measurement - pose->estimate().map( _point );
}

virtual void linearizeOplus()
{
g2o::VertexSE3Expmap* pose = static_cast<g2o::VertexSE3Expmap *>(_vertices[0]);
g2o::SE3Quat T(pose->estimate());
Eigen::Vector3d xyz_trans = T.map(_point);
double x = xyz_trans[0];
double y = xyz_trans[1];
double z = xyz_trans[2];

_jacobianOplusXi(0,0) = 0;
_jacobianOplusXi(0,1) = -z;
_jacobianOplusXi(0,2) = y;
_jacobianOplusXi(0,3) = -1;
_jacobianOplusXi(0,4) = 0;
_jacobianOplusXi(0,5) = 0;

_jacobianOplusXi(1,0) = z;
_jacobianOplusXi(1,1) = 0;
_jacobianOplusXi(1,2) = -x;
_jacobianOplusXi(1,3) = 0;
_jacobianOplusXi(1,4) = -1;
_jacobianOplusXi(1,5) = 0;

_jacobianOplusXi(2,0) = -y;
_jacobianOplusXi(2,1) = x;
_jacobianOplusXi(2,2) = 0;
_jacobianOplusXi(2,3) = 0;
_jacobianOplusXi(2,4) = 0;
_jacobianOplusXi(2,5) = -1;
}

bool read ( istream& in ) {}
bool write ( ostream& out ) const {}
protected:
Eigen::Vector3d _point;
};



int main ( int argc, char** argv )
{
if (argc != 5) {
cout<<"usage: pose_estimation_3d3d img1 img2 depth1 depth2"<<endl;
return 1;
}

//1.读取图像
Mat img_1 = imread ( argv[1], CV_LOAD_IMAGE_COLOR );
Mat img_2 = imread ( argv[2], CV_LOAD_IMAGE_COLOR );

//2.特征匹配
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;

//3.建立3D点
Mat depth1 = imread(argv[3], CV_LOAD_IMAGE_UNCHANGED); // 深度图为16位无符号数,单通道图像
Mat depth2 = imread(argv[4], CV_LOAD_IMAGE_UNCHANGED);
Mat K = (Mat_<double> (3,3) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1);
vector<Point3f> pts1, pts2;

for (DMatch m : matches) {
ushort d1 = depth1.ptr<unsigned short> ( int ( keypoints_1[m.queryIdx].pt.y ) ) [ int ( keypoints_1[m.queryIdx].pt.x ) ];
ushort d2 = depth2.ptr<unsigned short> ( int ( keypoints_2[m.trainIdx].pt.y ) ) [ int ( keypoints_2[m.trainIdx].pt.x ) ];
if ( d1==0 || d2==0 ) continue; // bad depth

Point2d p1 = pixel2cam ( keypoints_1[m.queryIdx].pt, K );
Point2d p2 = pixel2cam ( keypoints_2[m.trainIdx].pt, K );
float dd1 = float ( d1 ) /5000.0;
float dd2 = float ( d2 ) /5000.0;
pts1.push_back ( Point3f ( p1.x*dd1, p1.y*dd1, dd1 ) );
pts2.push_back ( Point3f ( p2.x*dd2, p2.y*dd2, dd2 ) );
}
cout << "3d-3d pairs: " << pts1.size() << endl;

//SVD方法求解
Mat R, t;
pose_estimation_3d3d ( pts1, pts2, R, t );
cout << endl << "ICP via SVD results: " << endl;
cout << "R = " << R << endl;
cout << "t = " << t << endl;
cout << "R_inv = " << R.t() << endl;
cout << "t_inv = " << -R.t() * t << endl;

//BA优化
cout << endl << "calling bundle adjustment" << endl;
bundleAdjustment( pts1, pts2, R, t );

// verify p1 = R*p2 + t
cout << endl;
for (int i = 0; i < 5; i++){
cout << "p1 = " << pts1[i] << endl;
cout << "p2 = " << pts2[i] << endl;
cout << "(R*p2+t) = "<<
R * (Mat_<double>(3,1)<<pts2[i].x, pts2[i].y, pts2[i].z) + t << endl;
cout << endl;
}
}


//特征匹配函数
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();
//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] );
}
}
}



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 pose_estimation_3d3d (
const vector<Point3f>& pts1,
const vector<Point3f>& pts2,
Mat& R, Mat& t
){
Point3f p1, p2; // center of mass
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<Point3f> q1(N), q2(N); // remove the center
for (int i = 0; i < N; i++){
q1[i] = pts1[i] - p1;
q2[i] = pts2[i] - p2;
}

// 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;

// SVD on W
Eigen::JacobiSVD<Eigen::Matrix3d> svd ( W, Eigen::ComputeFullU|Eigen::ComputeFullV );
Eigen::Matrix3d U = svd.matrixU();
Eigen::Matrix3d V = svd.matrixV();

if (U.determinant() * V.determinant() < 0){
for (int x = 0; x < 3; ++x){
U(x, 2) *= -1;
}
}

cout<<"U="<<U<<endl;
cout<<"V="<<V<<endl;

Eigen::Matrix3d R_ = U* ( V.transpose() );
Eigen::Vector3d t_ = Eigen::Vector3d ( p1.x, p1.y, p1.z ) - R_ * Eigen::Vector3d ( p2.x, p2.y, p2.z );

// convert to cv::Mat
R = ( Mat_<double> ( 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_<double> ( 3,1 ) << t_ ( 0,0 ), t_ ( 1,0 ), t_ ( 2,0 ) );
}


//BA优化
void bundleAdjustment (
const vector< Point3f >& pts1,
const vector< Point3f >& pts2,
Mat& R, Mat& t ) {
// 初始化g2o
typedef g2o::BlockSolver< g2o::BlockSolverTraits<6,3> > Block; // pose维度为 6, landmark 维度为 3
Block::LinearSolverType* linearSolver = new g2o::LinearSolverEigen<Block::PoseMatrixType>(); // 线性方程求解器
Block* solver_ptr = new Block( linearSolver ); // 矩阵块求解器
g2o::OptimizationAlgorithmGaussNewton* solver = new g2o::OptimizationAlgorithmGaussNewton( solver_ptr );
g2o::SparseOptimizer optimizer;
optimizer.setAlgorithm( solver );

// vertex
g2o::VertexSE3Expmap* pose = new g2o::VertexSE3Expmap(); // camera pose
pose->setId(0);
pose->setEstimate( g2o::SE3Quat(
Eigen::Matrix3d::Identity(),
Eigen::Vector3d( 0,0,0 )
) );
optimizer.addVertex( pose );

// edges
int index = 1;
vector<EdgeProjectXYZRGBDPoseOnly*> edges;
for ( size_t i=0; i<pts1.size(); i++ )
{
EdgeProjectXYZRGBDPoseOnly* edge = new EdgeProjectXYZRGBDPoseOnly(
Eigen::Vector3d(pts2[i].x, pts2[i].y, pts2[i].z) );
edge->setId( index );
edge->setVertex( 0, dynamic_cast<g2o::VertexSE3Expmap*> (pose) );
edge->setMeasurement( Eigen::Vector3d(
pts1[i].x, pts1[i].y, pts1[i].z) );
edge->setInformation( Eigen::Matrix3d::Identity()*1e4 );
optimizer.addEdge(edge);
index++;
edges.push_back(edge);
}

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<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;

}

(2)编译

mkdir build
cd build
cmake ..
make
cd ..
build/pose_estimation_3d3d 1.png 1_depth.png 2.png 2_depth.png