3D-3D座標 SVD奇異值分解 ICP迭代最近點 G2O優化 求解 求旋轉平移矩陣 R t
阿新 • • 發佈:2019-01-31
* 迭代最近點 Iterative Closest Point, ICP求解 3D座標 到 3D座標的轉換矩陣(不用求解距離 鐳射SLAM 以及 RGB-D SLAM) |
* 使用 線性代數SVD奇異值分解 或者 非線性優化方法 求解 |
* 使用深度圖將 平面圖 轉化成 3維點 |
* 特徵點匹配 得到 |
* 三維點對 P={p1, p2, ... ,pn} P' = {p1', p2', ... ,pn'} |
* 存在 旋轉矩陣R 和 平移矩陣t |
* 使得 pi = R* pi' + t |
* 當在鐳射SLAM直接使用 三維點進行 匹配(距離最近)得到3D點對(鐳射資料 特徵不夠豐富,匹配得到的點誤匹配的多) |
* 求解方法為 ICP Iterative Closet Point 迭代最近點 |
* 【1】 線性代數求解 SVD奇異值分解方法 |
* 誤差 ei = pi - (R*pi' + t) |
* 最小化誤差和 min (sum(ei^2)) ; e^2 = (pi-p - R*(pi' - p'))^2 + (p - R*p' - t)^2得到 R t |
* (1) 計算兩組 點集的質心位置 p 、 p‘ ,然後計算每個點的去質心座標 qi = pi - p qi’ = pi' - p‘ |
* (2) min(sum(qi - R * qi')^2) >>> 得到 旋轉矩陣R |
* (3) 有R計算 t t = p - R * p' |
* (qi - R * qi')^2 = qi轉置 * qi - 2*qi轉置 * R * qi + qi轉置 * R轉置* R * qi 第一項與R無關 第三項 應為 R轉置* R = I |
* qi轉置 * R * qi W= sum(qi * qi轉置) = U * 對角矩陣 * V轉置 奇異值分解 R= U * V轉置 |
* 【2】 非線性優化方法 |
* ei = pi -exp(f) * pi' = P - P‘ 李代數形式 的 變換矩陣 對誤差求導 得到 迭代優化 梯度 |
* 3×6的雅克比矩陣 誤差 對應的 導數 優化變數更新 增量 |
* e 對 ∇f的導數 = P'對∇f的偏導數 |
* P'對∇f的偏導數 = [ I -P'叉乘矩陣] 3*6大小 平移在前 旋轉在後 |
* = [ 1 0 0 0 Z' -Y' |
* 0 1 0 -Z' 0 X' |
* 0 0 1 Y' -X 0] |
* 旋轉在前 平移在後 |
* = [ 0 Z' -Y' 1 0 0 |
* -Z' 0 X' 0 1 0 |
* Y' -X 0 0 0 1] |
* J = - P'對∇f的偏導數 |
* = [ 0 -Z' Y' -1 0 0 |
* Z' 0 -X' 0 -1 0 |
-Y' X’ 0 0 0 -1]
#include <iostream>//輸入輸出流
// opencv
#include <opencv2/core/core.hpp>
#include <opencv2/features2d/features2d.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/calib3d/calib3d.hpp>
// Eigen3 矩陣
#include <Eigen/Core>
#include <Eigen/Geometry>
#include <Eigen/SVD>
// 非線性優化演算法 圖優化 G2O
#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>// 定義好的頂點型別 和 誤差 變數更新演算法 6維度 優化變數 例如 相機 位姿
#include <chrono>//演算法計時
using namespace std;//標準庫 名稱空間
using namespace cv; //opencv庫名稱空間
//特徵匹配 計算匹配點對
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 );
//ICP求解 3D- 3D 點對 求解 R T 使用 線性代數SVD奇異值分解
void pose_estimation_3d3d (
const vector<Point3f>& pts1,//3D
const vector<Point3f>& pts2,//3D
Mat& R, Mat& t//求解得到的 旋轉矩陣 和 平移矩陣
);
//g2o_BundleAdjustment 優化 計算旋轉和平移
//ICP演算法求解3D-3D點對的 轉換矩陣後使用 圖優化 進行優化
void bundleAdjustment (
const vector< Point3f >& pts1,//3D點
const vector< Point3f >& pts2,//3D點
Mat& R, Mat& t//初始R T 以及優化更新後 的 量
);
// 需自定義 邊型別 誤差項g2o edge
// 誤差模型—— 曲線模型的邊, 模板引數:觀測值維度(輸入的引數維度),型別,連線頂點型別(優化變數系統定義好的頂點 或者自定義的頂點)
// 3D點—3D點的邊
class EdgeProjectXYZRGBDPoseOnly : public g2o::BaseUnaryEdge<3, Eigen::Vector3d, g2o::VertexSE3Expmap>//基礎一元 邊型別
{
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;// 類成員 有Eigen 變數時需要 顯示 加此句話 巨集定義
EdgeProjectXYZRGBDPoseOnly( const Eigen::Vector3d& point ) : _point(point) {}//直接賦值 觀測值 3D點
// 誤差計算
virtual void computeError()
{
const g2o::VertexSE3Expmap* pose = static_cast<const g2o::VertexSE3Expmap*> ( _vertices[0] );//0號頂點為 位姿 型別強轉
// measurement is p, point is p'
_error = _measurement - pose->estimate().map( _point );//對觀測點 進行 變換 後 與測量值做差 得到 誤差
}
// 3d-3d自定義求解器
virtual void linearizeOplus()
{
g2o::VertexSE3Expmap* pose = static_cast<g2o::VertexSE3Expmap *>(_vertices[0]);//0號頂點為 位姿 型別強轉
g2o::SE3Quat T(pose->estimate());//得到 變換矩陣
Eigen::Vector3d xyz_trans = T.map(_point);//對點進行變換
double x = xyz_trans[0];//變換後的 x y z
double y = xyz_trans[1];
double z = xyz_trans[2];
// 3×6的雅克比矩陣 誤差 對應的 導數 優化變數更新 增量
/*
* P'對∇f的偏導數 = [ I -P'叉乘矩陣] 3*6大小 平移在前 旋轉在後
* = [ 1 0 0 0 Z' -Y'
* 0 1 0 -Z' 0 X'
* 0 0 1 Y' -X 0]
* 旋轉在前 平移在後
* = [ 0 Z' -Y' 1 0 0
* -Z' 0 X' 0 1 0
* Y' -X 0 0 0 1]
*
* J = - P'對∇f的偏導數
* = [ 0 -Z' Y' -1 0 0
* Z' 0 -X' 0 -1 0
* -Y' X’ 0 0 0 -1]
*/
_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<<"用法: 。、pose_estimation_3d3d 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 depth1 = imread ( argv[3], CV_LOAD_IMAGE_UNCHANGED ); // 深度圖為16位無符號數,單通道影象
Mat depth2 = imread ( argv[4], CV_LOAD_IMAGE_UNCHANGED ); // 深度圖為16位無符號數,單通道影象
Mat K = ( Mat_<double> ( 3,3 ) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1 );// 相機內參,TUM Freiburg2
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 ) // bad depth
continue;
Point2d p1 = pixel2cam ( keypoints_1[m.queryIdx].pt, K );//畫素點轉換成 相機座標系下點
Point2d p2 = pixel2cam ( keypoints_2[m.trainIdx].pt, K );//(x,y,1) 歸一化座標平面上的點
float dd1 = float ( d1 ) /1000.0;//深度 尺度 原來單位為mm 變成 m
float dd2 = float ( d2 ) /1000.0;
//3D點
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 點對數量: "<<pts1.size() <<endl;
Mat R, t;
cout<<"3d-3d 點對利用線性代數SVD奇異值分解求解變換矩陣"<<endl;
/* (1) 計算兩組 點集的質心位置 p 、 p‘ ,然後計算每個點的去質心座標 qi = pi - p qi’ = pi' - p‘
* (2) min(sum(qi - R * qi')^2) >>> 得到 旋轉矩陣R
* (3) 有R計算 t t = p - R * p'
*
* (qi - R * qi')^2 = qi轉置 * qi - 2*qi‘轉置 * R * qi + qi‘轉置 * R轉置* R * qi’ 第一項與R無關 第三項 應為 R轉置* R = I
*
* qi轉置 * R * qi W= sum(qi * qi’轉置) = U * 對角矩陣 * V轉置 奇異值分解 R= U * V轉置
* t = p - R * p'
*/
pose_estimation_3d3d ( pts1, pts2, R, t );
cout<<"迭代最近點 ICP 通過 SVD 分解: "<<endl;
cout<<"2-1 旋轉矩陣 R = "<<R<<endl;//第二張圖到第一張圖的轉換
cout<<"平移矩陣 t = "<<t<<endl;
cout<<"1-2 旋轉矩陣 R_inv = "<<R.t() <<endl;//第一張圖到第二張圖的轉換
cout<<"t_inv = "<<-R.t() *t<<endl;
cout<<"非線性優化方法 bundle adjustment 求解"<<endl;
bundleAdjustment( pts1, pts2, R, t );
// 驗證 verify p1 = R*p2 + t
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] );
}
}
}
// 畫素座標變換到 相機 歸一化平面上 u,v --->>> (x,y,1)
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 )
);
}
// 【1】 線性代數求解 SVD奇異值分解方法
/* (1) 計算兩組 點集的質心位置 p 、 p‘ ,然後計算每個點的去質心座標 qi = pi - p qi’ = pi' - p‘
* (2) min(sum(qi - R * qi')^2) >>> 得到 旋轉矩陣R
* (3) 有R計算 t t = p - R * p'
*
* (qi - R * qi')^2 = qi轉置 * qi - 2*qi‘轉置 * R * qi + qi‘轉置 * R轉置* R * qi’ 第一項與R無關 第三項 應為 R轉置* R = I
*
* qi轉置 * R * qi W= sum(qi * qi’轉置) = U * 對角矩陣 * V轉置 奇異值分解 R= U * V轉置
* t = p - R * p'
*/
void pose_estimation_3d3d (
const vector<Point3f>& pts1,//3D點容器
const vector<Point3f>& pts2,
Mat& R, Mat& t
)
{
//【1】 求中心點
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);
// 【2】得到去中心座標
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;
}
// 【3】計算需要進行奇異值分解的 W = sum(qi * qi’轉置) 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;
// 【4】對 W 進行SVD 奇異值分解
Eigen::JacobiSVD<Eigen::Matrix3d> svd ( W, Eigen::ComputeFullU|Eigen::ComputeFullV );
Eigen::Matrix3d U = svd.matrixU();
Eigen::Matrix3d V = svd.matrixV();
cout<<"U="<<U<<endl;
cout<<"V="<<V<<endl;
// 【5】計算旋轉 和平移矩陣 R 和 t
// R= U * V轉置
Eigen::Matrix3d R_ = U* ( V.transpose() );
// t = p - R * p'
Eigen::Vector3d t_ = Eigen::Vector3d ( p1.x, p1.y, p1.z ) - R_ * Eigen::Vector3d ( p2.x, p2.y, p2.z );
// 【6】格式轉換 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 ) );
}
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) );//點2
edge->setId( index );
edge->setVertex( 0, dynamic_cast<g2o::VertexSE3Expmap*> (pose) );//頂點
edge->setMeasurement( Eigen::Vector3d(
pts1[i].x, pts1[i].y, pts1[i].z) );// 點1 = T * 點2 = 點1'
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);// 最大優化次數為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<<"優化後的 R t :"<<endl;
cout<<"變換矩陣 T = "<<endl<<Eigen::Isometry3d( pose->estimate() ).matrix()<<endl;
}