- 攜帶攝像頭的機器人在運動過程當中,會連續性地獲取多幀圖像,輔助其感知周圍環境和自身運動。時間序列上相連的兩幅或多幅圖像,一般存在相同的景物,只是它們在圖像中的位置不一樣。而位置的變換偏偏暗含了相機的運動,這時就須要相鄰圖像間的類似性匹配。
- 選取一大塊圖像區域進行運動估計是不可取的。已知圖像在計算機內部是以數字矩陣的形式存儲的,[如灰度圖的每一個元素表明了單個像素的灰度值]。而對於點的提取和匹配較爲方便,且和數字值對應,因此引入圖像特徵點輔助估計相機的運動。
特徵點的提取是與關鍵點和描述子牢牢關聯的;前端
這裏以ORB爲例展現特徵點的提取過程。python
能夠被認爲是特徵點 (N 一般取 12,即爲 FAST-12。其它經常使用的 N 取值爲 9 和 11, 他們分別被稱爲 FAST-9, FAST-11)。
下圖較爲清晰的描述了角點的檢測:ios
爲了提升算法效率,能夠跳躍式檢測每一個像素鄰域圓上的像素值,如第1,5,9,13個。算法
爲了不角點集中,需採用非極大值抑制,即在必定區域內僅保留響應極大值的角點。後端
Oriented FAST關鍵點:因爲FAST角點存在必定的問題,ORB關鍵點對其進行了改進。優化
- FAST特徵點數量大且不肯定。
咱們每每但願對圖像提取固定數量的特徵,這樣易於計算和匹配。改進的方式爲:指定最終要提取的角點數量N,對原始提取的FAST角點分別計算Harris響應值,而後選取前N個具備最大響應值的角點。ui
- FAST角點不具備方向信息,並且選取半徑爲3的鄰域圓也存在尺度問題。
ORB關鍵點添加了對尺度和旋轉的描述。其中,尺度不變性經過構建圖像金字塔 [ 同一圖像的不一樣分辨率表示 ],在每一層進行角點檢測;spa
旋轉不變性採用灰度質心法實現,質心是指以圖像塊灰度值做爲權重的中心,其具體步驟以下——來自視覺SLAM十四講:設計
在一個小的圖像塊 B 中,定義圖像塊的矩爲:3d
這裏的矩實際爲HU矩中的原點矩。其通常用來識別圖像中大的物體,可以較好地描述物體的形狀,要求圖像的紋理特徵不能太複雜。
經過矩能夠找到圖像塊的質心:
鏈接圖像塊的幾何中心 O 與質心 C,獲得一個方向向量,因而特徵點的方向能夠定義爲:
這裏θ即爲旋轉的角度描述。
知識點拓展:圖像的幾何矩
- 在數學中,矩的本質是數學指望,即:
\[ \int x · f(x) dx \]
其中f(x)表明x的機率密度。
在灰度圖像中,每一個像素點的值能夠當作該處的密度。對某個像素點的值求指望即獲得了圖像在該點處的矩。矩有原點矩(零階矩)、一階矩、二階矩;由零階矩和一階矩能夠計算某個形狀的重心,而二階矩能夠計算形狀的方向。
\[ 零階矩:M_{00} = \sum_{x,y} I(x,y) \]\[ 一階矩:M_{10} = \sum_{x,y} x·I(x,y);M_{01} = \sum_{x,y}y·I(x,y) \]
\[ 推出圖像的重心(質心)座標:x_c = \frac{M_{10}}{M_{00}};y_c = \frac{M_{01}}{M_{00}} \]
這種質心計算方法的優勢爲:對噪聲不敏感。
\[ 二階矩:M_{20} = \sum x^2 · I(x,y);M_{02} = \sum y^2 · I(x,y);M_{11}=\sum x·y·I(x,y) \]
\[ 則物體的形狀方向:θ = \frac{1}{2}arctan(\frac{2b}{a-c}),θ∈[-90°,90°] \]
\[ 其中,a=\frac{M_{20}}{M_{00}}-x_c^2;b=\frac{M_{11}}{M_{00}}-x_cy_c;c=\frac{M_{02}}{M_{00}}-y_c^2; \]
圖像的矩具備旋轉、平移、尺度等的不變性,又稱爲不變矩。
BRIEF描述子:一種二進制描述子,向量由多個0和1組成,這裏0和1表示關鍵點附近的兩個像素(如p,q)的大小關係——p>q,取1;p<q,取0。而p和q的選取是按照某種機率分佈隨機選取。
優勢:速度快,存儲方便;適用於實時的圖像匹配。
改進BRIEF描述子(rBRIEF):加入旋轉因子,改進旋轉不變性;改進特徵點描述子的相關性(便可區分性),對誤匹配率影響較大。
特徵匹配實際上描述的是連續的兩張圖像中景物的對應關係,以此來估計相機的運動。
匹配方法:
暴力匹配。即圖像1中取特徵點集合A,圖像2中取特徵點集合B,對A中的每個特徵點,依次與B中全部的特徵點測量二者描述子的距離,而後排序,取距離最近的做爲匹配的兩個特徵點。
這裏,描述子距離表示了兩張圖片兩個特徵點之間的類似程度,在實際應用中能夠取不一樣的距離度量範數。如:對於浮點類型,使用歐氏距離;對於二進制類型,使用漢明距離[即兩個二進制串之間不一樣位數的個數]。
缺點:計算量隨特徵點數量增大呈遞增趨勢。
快速近似最近鄰(FLANN)。集成於OpenCV,適合於匹配點數量極多的狀況。
註釋寫在了源代碼裏。
#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; } //-- 讀取圖像,以RGB格式讀取 Mat img_1 = imread ( argv[1], CV_LOAD_IMAGE_COLOR ); Mat img_2 = imread ( argv[2], CV_LOAD_IMAGE_COLOR ); //-- 初始化 /* * 1. FeatureDetector特徵檢測器類,經過建立該類對象來使用多種特徵檢測方法。【用於檢測指定特徵點的角點位置】 OpenCV2.4.3中提供了10種特徵檢測方法:FAST,SIFT,SURF,ORB,HARRIS,SimpleBlob,STAR,MSER,GFTT,Dense。 這裏使用ORB特徵檢測方法 * 2. DescriptorExtractor特徵描述子提取類,提供了一些特徵描述子提取的算法。 其能夠針對圖像關鍵點,計算其特徵描述子,其能夠被表達成密集(dense),即固定維數的向量。 其計算方式爲每隔固定個像素計算。 一個特徵描述子是一個向量,特徵描述子的集合爲Mat格式,每一行是一個關鍵點的特徵描述子。 OpenCV支持四種類型的特徵描述子提取方法:SIFT,SURF,ORB,BRIEF。 * 3. DescriptorMatcher特徵匹配類,提供了一些特徵點匹配的方法。 該類主要包含圖像對之間的匹配以及圖像和一個圖像集之間的匹配。 OpenCV2中的特徵匹配方法都繼承自該類。 對於誤匹配狀況,提供了KNNMatch方法。 */ std::vector<KeyPoint> keypoints_1, keypoints_2; // 聲明存放兩張圖片各自關鍵點的向量 Mat descriptors_1, descriptors_2; // 兩張圖片特徵點的描述子,形式爲向量 Ptr<FeatureDetector> detector = ORB::create(); // 建立FeatureDetector類型的指針detector Ptr<DescriptorExtractor> descriptor = ORB::create(); // ORB特徵描述子提取指針 // Ptr<FeatureDetector> detector = FeatureDetector::create(detector_name); // Ptr<DescriptorExtractor> descriptor = DescriptorExtractor::create(descriptor_name); Ptr<DescriptorMatcher> matcher = DescriptorMatcher::create ( "BruteForce-Hamming" ); // 匹配時計算描述子之間的距離使用漢明距離 //-- 第一步:檢測 Oriented FAST 角點位置,使用detect方法,將其存入Keypoints變量中 detector->detect ( img_1,keypoints_1 ); detector->detect ( img_2,keypoints_2 ); //-- 第二步:根據角點位置計算 BRIEF 描述子,使用compute方法,將其存入descriptors變量中 descriptor->compute ( img_1, keypoints_1, descriptors_1 ); descriptor->compute ( img_2, keypoints_2, descriptors_2 ); /* * 繪製第一幅圖像的ORB特徵點,注意這裏要把圖片的名稱全改成英文才能正常顯示。 */ Mat outimg1; drawKeypoints( img_1, keypoints_1, outimg1, Scalar::all(-1), DrawMatchesFlags::DEFAULT ); imshow("ORB features.jpg",outimg1); //-- 第三步:對兩幅圖像中的BRIEF描述子進行匹配,使用 Hamming 距離 /* * Brute-Force(BF)匹配器,取第一個集合裏一個特徵的描述子並與第二個集合裏全部特徵的描述子計算距離,返回最近的特徵點。 其有兩個方法:BFMatcher.match()和BFMatcher.knnMatch(),前者返回最匹配的特徵點(僅一個),後者返回k個最匹配的特徵點,k由用戶指定。 */ vector<DMatch> matches; // DMatch類型的向量。 //BFMatcher matcher ( NORM_HAMMING ); matcher->match ( descriptors_1, descriptors_2, matches ); // 使用match方法,獲取最匹配的兩個特徵點(匹配的特徵點能夠有多對,均存放在matche中) //-- 第四步:匹配點對篩選 double min_dist=10000, max_dist=0; //找出全部匹配之間的最小距離和最大距離, 便是最類似的和最不類似的兩組點之間的距離 /* * descriptors的每行爲一個特徵點的描述子向量;圖像1中有多少個特徵點,matches中存儲多少個匹配的圖像2的特徵點相關類型 */ 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] ); } } //-- 第五步:繪製匹配結果,數量分別爲matches和good_matches 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 ( "all match features.jpg", img_match ); // 注意這裏圖片名要改爲英文 imshow ( "good match features.jpg", img_goodmatch ); waitKey(0); return 0; }
- 視覺SLAM主要分爲視覺前端和優化後端,前端即視覺里程計(VO),其做用是根據相鄰圖像的信息,估計相機運動,提供初始值給後端。
- 根據是否須要提取特徵,VO分爲特徵點法和直接法。
用於3D-3D的位姿估計,即兩張圖像爲3D圖像(如RGB-D相機獲取的圖像),其中的3D特徵點集合已經提取和匹配好。
ICP即爲迭代最近點,僅考慮兩組3D點之間的變換,此時和相機無關。特徵點方法正好爲咱們提供了兩張圖像之間良好的匹配關係,ICP能夠據此進行運動估計。
利用線性代數方法的求解(SVD):由兩張圖片,獲得兩組匹配好的3D特徵點集合,這兩組一一對應的點之間具備歐氏變換關係,即集合1中的點能由集合2中的點經過變換矩陣獲得,即有R和T表示兩個點之間的關係。
匹配好的特徵點對會存在必定的偏差,定義偏差項,由偏差項構建最小二乘問題,即表示偏差平方和,求一個最優化問題,這裏是求使偏差平方和達到極小的R,t。
【理解:由於ICP問題求解的目的是得出相機的位姿估計,能夠理解爲當拍攝到第二幀圖像時相機的位置與拍攝第一幀圖像時相機原位置的變換關係,而變換關係能夠用歐氏矩陣R和t描述,而由匹配的特徵點對能夠描述多個相機位姿,這裏就涉及一個最優化問題,即構建最小二乘,求解使相機位姿相對最精確的R和t。】
[注:可是具體的求解數學公式沒看懂。]
利用非線性優化方法的求解:以迭代的方式找最優值。[一樣數學式沒看懂。]
源代碼提供了SVD和非線性優化兩種方法。
添加了一點關鍵註釋。
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 /* * g2o是一個圖優化庫,圖優化的本質仍然是非線性優化,而用圖的方式表示,可使問題可視化。 */ 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; } //-- 讀取圖像 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 ); // 理解這裏的K爲相機內參 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 ); float dd1 = float ( d1 ) /5000.0; // 深度值尺度縮放 float dd2 = float ( d2 ) /5000.0; pts1.push_back ( Point3f ( p1.x*dd1, p1.y*dd1, dd1 ) ); // 獲得特徵點的3D座標 pts2.push_back ( Point3f ( p2.x*dd2, p2.y*dd2, dd2 ) ); } cout<<"3d-3d pairs: "<<pts1.size() <<endl; Mat R, t; pose_estimation_3d3d ( pts1, pts2, R, t ); // 求得最優的R和t cout<<"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; cout<<"calling bundle adjustment"<<endl; bundleAdjustment( pts1, pts2, R, t ); // 非線性優化方法求解ICP問題 // 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; } }
還有feature_extraction.cpp中的特徵點提取、匹配和跟蹤的代碼,這個上邊已經分析過了。
繪製了光流法的原理圖