五 .3D-2D:PnP问题求解 非线性法BA

顶点是3D坐标(XYZ)相机位姿R t,误差项是重投影误差。把问题建模成一个最小二乘的图优化问题。

 

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

/****************自定义函数find_feature_matches********************************************************/

//参考一.特征提取

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

}

}

}

/****************自定义函数 pixel2cam********************************************************/

// 像素坐标p1,p1转相机归一化坐标x1 x2

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 )

);

}

/****************自定义函数 bundleAdjustmen********************************************************/

void bundleAdjustment (

const vector< Point3f > points_3d,

const vector< Point2f > points_2d,

const Mat& K,

Mat& R, Mat& t )

{

// 1.初始化g2o设定线性方程求解器Blocksolver和迭代算法

// pose 维度为 6, landmark 维度为 3

typedef g2o::BlockSolver< g2o::BlockSolverTraits<6,3> > Block;

// 线性方程求解器

Block::LinearSolverType* linearSolver = new g2o::LinearSolverCSparse<Block::PoseMatrixType>();

// 矩阵块求解器

Block* solver_ptr = new Block ( linearSolver );

// 梯度下降方法,从GN, LM, DogLeg 中选

g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg ( solver_ptr );

g2o::SparseOptimizer optimizer; // 图模型

optimizer.setAlgorithm ( solver ); // 设置求解器

//optimizer.setVerbose( true ); // 打开调试输出

//2.1 往图中增加顶点 pose

// 相机的李代数位姿,VertexSE3Expmap类

g2o::VertexSE3Expmap* pose = new g2o::VertexSE3Expmap();

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

//相机位姿类型SE3Quat,四元数+位移向量

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

 

// 2.2 图中增加顶点point

int index = 1;

for ( const Point3f p : points_3d ) // landmarks, c++11 for新用法for(:)遍历数组points_3d

{

//空间点位置类型,VertexSBAPointXYZ

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

}

 

// 相机内参K,CameraParameters类

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

 

// 2.3 图中增加边

index = 1;

for ( const Point2f p:points_2d )

{

//投影方程边类型EdgeProjectXYZ2UV

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

}

// 3 开始执行优化

optimizer.setVerbose ( true ); // 打开调试输出

optimizer.initializeOptimization();

optimizer.optimize ( 100 );

cout<<"T="<<endl<<Eigen::Isometry3d ( pose->estimate() ).matrix() <<endl;

}

 

 

/**************************************************************************************************************/

备注:

  • 相机位姿顶点类VertexSE3Expmap
  • 3D路标点类VertexSBAPointXYZ
  • 重投影误差边类EdgeProjectXYZ2UV

1、相机位姿顶点类VertexSE3Expmap使用了李代数表示相机位姿,而不是使用旋转矩阵和平移矩阵。

这是因为旋转矩阵是有约束的矩阵,它必须是正交矩阵且行列式为1。使用它作为优化变量就会引入额外的约束条件,从而增大优化的复杂度。而将旋转矩阵通过李群-李代数之间的转换关系转换为李代数表示,就可以把位姿估计变成无约束的优化问题,求解难度降低。

2、在重投影误差边类EdgeProjectXYZ2UV中,已经为相机位姿和3D点坐标推导了雅克比矩阵EdgeProjectXYZ2UV::linearizeOplus(),以计算迭代的增量方向。

void EdgeProjectXYZ2UVPoseOnly::linearizeOplus()

{

/**

* 这里说一下整体思路:

* 重投影误差的雅克比矩阵在书中P164页式7.45已经呈现,所以这里就是直接构造,

* 构造时发现需要变换后的空间点坐标,所以需要先求出。

*/

//1. 首先还是从顶点取出位姿

g2o::VertexSE3Expmap* pose = static_cast<g2o::VertexSE3Expmap*> ( _vertices[1] );

//2. 这由位姿构造一个四元数形式T

g2o::SE3Quat T ( pose->estimate() );

//3. 用T求得变换后的3D点坐标。T.map(p)就是T*p

g2o::VertexSBAPointXYZ* point_ = static_cast<g2o::VertexSBAPointXYZ*>(_vertices[0]);

Vector3d xyz_trans = T.map ( point_ );

//OK,到这步,变换后的3D点xyz坐标就分别求出来了,后面的z平方,纯粹是为了后面构造J时方便定义的,因为需要多处用到

double x = xyz_trans[0];

double y = xyz_trans[1];

double z = xyz_trans[2];

double z_2 = z*z;

// 相机参数

const CameraParameters* cam=static_cast<const CameraParameters*>(parameter(0));

//4. 直接各个元素构造J就好了,对照式7.45是一模一样的,2*6的矩阵。

_jacobianOplusXi ( 0,0 ) = x*y/z_2 *camera_->fx_;

_jacobianOplusXi ( 0,1 ) = - ( 1+ ( x*x/z_2 ) ) *camera_->fx_;

_jacobianOplusXi ( 0,2 ) = y/z * camera_->fx_;

_jacobianOplusXi ( 0,3 ) = -1./z * camera_->fx_;

_jacobianOplusXi ( 0,4 ) = 0;

_jacobianOplusXi ( 0,5 ) = x/z_2 * camera_->fx_;

_jacobianOplusXi ( 1,0 ) = ( 1+y*y/z_2 ) *camera_->fy_;

_jacobianOplusXi ( 1,1 ) = -x*y/z_2 *camera_->fy_;

_jacobianOplusXi ( 1,2 ) = -x/z *camera_->fy_;

_jacobianOplusXi ( 1,3 ) = 0;

_jacobianOplusXi ( 1,4 ) = -1./z *camera_->fy_;

_jacobianOplusXi ( 1,5 ) = y/z_2 *camera_->fy_;

}

}

 

/***************************************************************************************************************/

 

 

主函数

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

Mat img_2 = imread ( argv[2], 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 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 )

{

//d1是深度图,Mat类型的ptr是指针,获得像素点深度,首先得到行地址,之后列指针  (pt.y)[pt.x]

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;

 

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;

 

cout<<"calling bundle adjustment"<<endl;

 

bundleAdjustment ( pts_3d, pts_2d, K, R, t );

}

结果:

五 .3D-2D:PnP问题求解 非线性法BA