視覺slam十四講第七章課后習題7


版權聲明:本文為博主原創文章,轉載請注明出處:http://www.cnblogs.com/newneul/p/8544369.html

 7、題目要求:在ICP程序中,將空間點也作為優化變量考慮進來,程序應該如何書寫?最后結果會有何變化?

  分析:在ICP例程中,本書使用的是自定義的一個繼承BaseUnaryEdge的邊,從例子中的EdgeProjectXYZRGBDPoseOnly這個類在linearizeOplus中寫下了關於位姿節點的雅克比矩陣,里面也沒有相機模型參數模型(沒有涉及到相機內參),沒有關於空間坐標點的雅克比矩陣。通過書上175頁誤差函數,可以將空間點也作為優化變量,可在這個函數內部加入關於空間點的雅克比矩陣-R,因為優化空間點時會與位姿節點構成關系,所以在圖中我們將空間點和位姿節點鏈接起來,建立一個二元邊,仿照g2o::EdgeProjectXYZ2UV這個類的寫法。寫下修改后的類:

 1 class EdgeProjectXYZRGBDPoseOnly : public g2o::BaseBinaryEdge<3, Eigen::Vector3d,g2o::VertexSBAPointXYZ, g2o::VertexSE3Expmap>
 2 {
 3 public:
 4     EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
 5     EdgeProjectXYZRGBDPoseOnly( ) {}
 6 
 7     virtual void computeError()
 8     {
 9         const g2o::VertexSBAPointXYZ * point  = dynamic_cast< const g2o::VertexSBAPointXYZ *> ( _vertices[0] );
10         const g2o::VertexSE3Expmap * pose = dynamic_cast<const g2o::VertexSE3Expmap*> ( _vertices[1] );
11         // measurement is p, point is p'
12         //pose->estimate().map( _point );中用estimate()估計一個值后,然后用映射函數 就是旋轉加平移 將其_point映射到另一個相機坐標系下去
13         //觀測值 - 映射值 因為我們做的試驗是3D-3D 所以這里把第一幀的3D坐標當做測量值,然后把第二幀坐標映射到第一幀坐標系中
14         _error = _measurement - pose->estimate().map( point->estimate() );
15     }
16     //表示線性化 誤差函數 就是要計算雅克比矩陣
17     virtual void linearizeOplus()override final                //這里override 表示override覆蓋基類的同名同參函數, final表示派生類的某個函數不能覆蓋這個函數
18     {
19         g2o::VertexSE3Expmap* pose = dynamic_cast<g2o::VertexSE3Expmap *> (_vertices[1]);
20         g2o::VertexSBAPointXYZ * point = dynamic_cast< g2o::VertexSBAPointXYZ * > (_vertices[0] );
21         g2o::SE3Quat T(pose->estimate());
22         Eigen::Vector3d xyz_trans = T.map( point->estimate() );//映射到第二幀相機坐標系下的坐標值
23         double x = xyz_trans[0];                               //第一幀到第二幀坐標系下變換后的坐標值
24         double y = xyz_trans[1];
25         double z = xyz_trans[2];
26 
27         //關於空間點的雅克比矩陣-R
28         _jacobianOplusXi = -T.rotation().toRotationMatrix();
29 
30         //3x6的關於優化變量的雅克比矩陣 可以看書上p179頁 自己推到的結果
31         _jacobianOplusXj(0,0) = 0;
32         _jacobianOplusXj(0,1) = -z;
33         _jacobianOplusXj(0,2) = y;
34         _jacobianOplusXj(0,3) = -1;
35         _jacobianOplusXj(0,4) = 0;
36         _jacobianOplusXj(0,5) = 0;
37 
38         _jacobianOplusXj(1,0) = z;
39         _jacobianOplusXj(1,1) = 0;
40         _jacobianOplusXj(1,2) = -x;
41         _jacobianOplusXj(1,3) = 0;
42         _jacobianOplusXj(1,4) = -1;
43         _jacobianOplusXj(1,5) = 0;
44 
45         _jacobianOplusXj(2,0) = -y;
46         _jacobianOplusXj(2,1) = x;
47         _jacobianOplusXj(2,2) = 0;
48         _jacobianOplusXj(2,3) = 0;
49         _jacobianOplusXj(2,4) = 0;
50         _jacobianOplusXj(2,5) = -1;
51     }
52 
53     bool read ( istream& in ) {}
54     bool write ( ostream& out ) const {}
55 };

在BA優化過程中我們假定僅僅優化第二幀的空間點坐標,因此在g2o::SparseOptimizer中我們加入空間點為待優化節點,對應節點部分添加如下代碼:

 1 #if MyselfOptimizerMethod                                   //添加空間節點  並且按照書上的方式進行優化的
 2     int pointIndex = 1;                                     //因為上面的位姿節點就1個  所以我們這里標號為1
 3     for( auto &p: pts2 ){
 4         auto point = new g2o::VertexSBAPointXYZ();
 5         point->setId( pointIndex++ );
 6         point->setMarginalized( true );                     //設置邊緣化(必須設置 否則出錯)
 7         point->setEstimate( Eigen::Vector3d( p.x, p.y, p.z ) );
 8         optimizer.addVertex( point );
 9     }
10 #endif

對應邊的部分添加如下代碼:

  edge->setVertex( 0 , dynamic_cast< g2o::VertexSBAPointXYZ *> ( optimizer.vertex(index)) );
  edge->setVertex( 1 , dynamic_cast< g2o::OptimizableGraph::Vertex *> ( optimizer.vertex(0) ) );

在BA函數最后加入優化前后第二幀點的位置信息,僅僅以前三個點對為例:

1     cout<<"輸出優化后的point值:"<<endl;
2     for (int j = 0; j <3 ; ++j) {
3         cout<< dynamic_cast< g2o::VertexSBAPointXYZ * > ( optimizer.vertex(j+1) )->estimate()<<endl<<endl;//Eigen::Vector3d
4     }
5     cout<<endl<<"優化前的點:"<<endl;
6     for (int i = 0; i <3 ; ++i) {
7         cout<<pts2[i]<<endl<<endl;
8     }

需要注意的是自己在代碼開頭部分加入了一些配置信息的輸出:

 1 void printConfigInfo(){
 2     cout<<"This is the example from GaoXiang's book : ICP結果是第二幀到第一幀的RT."<<endl;
 3 #if BAOptimizer
 4 
 5     cout<<"BA Optimizer is Provided!"<<endl;
 6     #if ISBAProvideInitValue
 7     cout<<"The RT from ICP's result is Provided for BA as a initialization."<<endl;
 8     #else
 9     cout<<" But,Not provide initialization for BA!"<<endl;
10     #endif
11 
12     #if  MyselfOptimizerMethod
13     cout<<"優化了空間點和位姿節點!"<<endl;
14     #else
15     cout<<"未對空間點進行優化!"<<endl;
16     #endif
17 
18 #endif
19 }

在最開始配置區部分,讀者可以自己調節系統如何輸出,配置區代碼如下:

 1 /*+++++++++++++++++++++++++++++++++++++++++配置信息+++++++++++++++++++++++++++++++++++++++++++++***/
 2 
 3 #define  MyselfOptimizerMethod  1   //  1: 課后習題7代碼結果
 4                                     //  0: 3d-3d書上例子
 5 #define  ISBAProvideInitValue   0   //  1: 用ICP結果為BA提供初值
 6                                     //  0: 用單位矩陣I和0平移向量作為初始值
 7 
 8 #define  BAOptimizer            1   //  1: 加入BA優化
 9                                     //  0: 不加入BA優化
10 
11 /*+++++++++++++++++++++++++++++++++++++++++End配置信息+++++++++++++++++++++++++++++++++++++++++++++*/

總體代碼以及結果圖如下:

  1 #include <iostream>
  2 #include <opencv2/core/core.hpp>
  3 #include <opencv2/features2d/features2d.hpp>
  4 #include <opencv2/highgui/highgui.hpp>
  5 #include <opencv2/calib3d/calib3d.hpp>
  6 #include <Eigen/Core>
  7 #include <Eigen/Geometry>
  8 #include <Eigen/SVD>
  9 #include <g2o/core/base_vertex.h>
 10 #include <g2o/core/base_unary_edge.h>
 11 #include <g2o/core/block_solver.h>
 12 #include <g2o/core/optimization_algorithm_gauss_newton.h>
 13 #include <g2o/solvers/eigen/linear_solver_eigen.h>
 14 #include <g2o/types/sba/types_six_dof_expmap.h>
 15 #include <chrono>
 16 #include <g2o/core/optimization_algorithm_levenberg.h>
 17 
 18 using namespace std;
 19 using namespace cv;
 20 /*+++++++++++++++++++++++++++++++++++++++++配置信息+++++++++++++++++++++++++++++++++++++++++++++***/
 21 
 22 #define  MyselfOptimizerMethod  1   //  1: 課后習題7代碼結果
 23                                     //  0: 3d-3d書上例子
 24 #define  ISBAProvideInitValue   0   //  1: 用ICP結果為BA提供初值
 25                                     //  0: 用單位矩陣I和0平移向量作為初始值
 26 
 27 #define  BAOptimizer            1   //  1: 加入BA優化
 28                                     //  0: 不加入BA優化
 29 
 30 /*+++++++++++++++++++++++++++++++++++++++++End配置信息+++++++++++++++++++++++++++++++++++++++++++++*/
 31 
 32 void find_feature_matches (
 33     const Mat& img_1, const Mat& img_2,
 34     std::vector<KeyPoint>& keypoints_1,
 35     std::vector<KeyPoint>& keypoints_2,
 36     std::vector< DMatch >& matches );
 37 
 38 // 像素坐標轉相機歸一化坐標
 39 Point2d pixel2cam ( const Point2d& p, const Mat& K );
 40 
 41 void pose_estimation_3d3d (
 42     const vector<Point3f>& pts1,
 43     const vector<Point3f>& pts2,
 44     Mat& R, Mat& t
 45 );
 46 
 47 #if BAOptimizer
 48 void bundleAdjustment (
 49         const vector< Point3f >& pts1,
 50         const vector< Point3f >& pts2,
 51         Mat& R, Mat& t );
 52 
 53     #if MyselfOptimizerMethod
 54 //課后習題7題
 55 class EdgeProjectXYZRGBDPoseOnly : public g2o::BaseBinaryEdge<3, Eigen::Vector3d,g2o::VertexSBAPointXYZ, g2o::VertexSE3Expmap>
 56 {
 57 public:
 58     EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
 59     EdgeProjectXYZRGBDPoseOnly( ) {}
 60 
 61     virtual void computeError()
 62     {
 63         const g2o::VertexSBAPointXYZ * point  = dynamic_cast< const g2o::VertexSBAPointXYZ *> ( _vertices[0] );
 64         const g2o::VertexSE3Expmap * pose = dynamic_cast<const g2o::VertexSE3Expmap*> ( _vertices[1] );
 65         // measurement is p, point is p'
 66         //pose->estimate().map( _point );中用estimate()估計一個值后,然后用映射函數 就是旋轉加平移 將其_point映射到另一個相機坐標系下去
 67         //觀測值 - 映射值 因為我們做的試驗是3D-3D 所以這里把第一幀的3D坐標當做測量值,然后把第二幀坐標映射到第一幀坐標系中
 68         _error = _measurement - pose->estimate().map( point->estimate() );
 69     }
 70     //表示線性化 誤差函數 就是要計算雅克比矩陣
 71     virtual void linearizeOplus()override final                //這里override 表示override覆蓋基類的同名同參函數, final表示派生類的某個函數不能覆蓋這個函數
 72     {
 73         g2o::VertexSE3Expmap* pose = dynamic_cast<g2o::VertexSE3Expmap *> (_vertices[1]);
 74         g2o::VertexSBAPointXYZ * point = dynamic_cast< g2o::VertexSBAPointXYZ * > (_vertices[0] );
 75         g2o::SE3Quat T(pose->estimate());
 76         Eigen::Vector3d xyz_trans = T.map( point->estimate() );//映射到第二幀相機坐標系下的坐標值
 77         double x = xyz_trans[0];                               //第一幀到第二幀坐標系下變換后的坐標值
 78         double y = xyz_trans[1];
 79         double z = xyz_trans[2];
 80 
 81         //關於空間點的雅克比矩陣-R
 82         _jacobianOplusXi = -T.rotation().toRotationMatrix();
 83 
 84         //3x6的關於優化變量的雅克比矩陣 可以看書上p179頁 自己推到的結果
 85         _jacobianOplusXj(0,0) = 0;
 86         _jacobianOplusXj(0,1) = -z;
 87         _jacobianOplusXj(0,2) = y;
 88         _jacobianOplusXj(0,3) = -1;
 89         _jacobianOplusXj(0,4) = 0;
 90         _jacobianOplusXj(0,5) = 0;
 91 
 92         _jacobianOplusXj(1,0) = z;
 93         _jacobianOplusXj(1,1) = 0;
 94         _jacobianOplusXj(1,2) = -x;
 95         _jacobianOplusXj(1,3) = 0;
 96         _jacobianOplusXj(1,4) = -1;
 97         _jacobianOplusXj(1,5) = 0;
 98 
 99         _jacobianOplusXj(2,0) = -y;
100         _jacobianOplusXj(2,1) = x;
101         _jacobianOplusXj(2,2) = 0;
102         _jacobianOplusXj(2,3) = 0;
103         _jacobianOplusXj(2,4) = 0;
104         _jacobianOplusXj(2,5) = -1;
105     }
106 
107     bool read ( istream& in ) {}
108     bool write ( ostream& out ) const {}
109 };
110     #else
111 // g2o edge 邊代表誤差  所以在里面要override一個computerError函數
112 class EdgeProjectXYZRGBDPoseOnly : public g2o::BaseUnaryEdge<3, Eigen::Vector3d, g2o::VertexSE3Expmap>
113 {
114 public:
115     EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
116     EdgeProjectXYZRGBDPoseOnly( const Eigen::Vector3d& point ) : _point(point) {}
117 
118     virtual void computeError()
119     {
120         const g2o::VertexSE3Expmap* pose = dynamic_cast<const g2o::VertexSE3Expmap*> ( _vertices[0] );
121         // measurement is p, point is p'
122         //pose->estimate().map( _point );中用estimate()估計一個值后,然后用映射函數 就是旋轉加平移 將其_point映射到另一個相機坐標系下去
123         //觀測值 - 映射值 因為我們做的試驗是3D-3D 所以這里把第一幀的3D坐標當做測量值,然后把第二幀坐標映射到第一幀坐標系中
124         _error = _measurement - pose->estimate().map( _point );
125     }
126     //表示線性化 誤差函數 就是要計算雅克比矩陣
127     virtual void linearizeOplus()
128     {
129         g2o::VertexSE3Expmap* pose = dynamic_cast<g2o::VertexSE3Expmap *>(_vertices[0]);
130         g2o::SE3Quat T(pose->estimate());
131         Eigen::Vector3d xyz_trans = T.map(_point);//映射到第二幀相機坐標系下的坐標值
132         double x = xyz_trans[0];                  //第一幀到第二幀坐標系下變換后的坐標值
133         double y = xyz_trans[1];
134         double z = xyz_trans[2];
135 
136         //3x6的關於優化變量的雅克比矩陣 可以看書上p179頁 自己推到的結果
137         _jacobianOplusXi(0,0) = 0;
138         _jacobianOplusXi(0,1) = -z;
139         _jacobianOplusXi(0,2) = y;
140         _jacobianOplusXi(0,3) = -1;
141         _jacobianOplusXi(0,4) = 0;
142         _jacobianOplusXi(0,5) = 0;
143 
144         _jacobianOplusXi(1,0) = z;
145         _jacobianOplusXi(1,1) = 0;
146         _jacobianOplusXi(1,2) = -x;
147         _jacobianOplusXi(1,3) = 0;
148         _jacobianOplusXi(1,4) = -1;
149         _jacobianOplusXi(1,5) = 0;
150 
151         _jacobianOplusXi(2,0) = -y;
152         _jacobianOplusXi(2,1) = x;
153         _jacobianOplusXi(2,2) = 0;
154         _jacobianOplusXi(2,3) = 0;
155         _jacobianOplusXi(2,4) = 0;
156         _jacobianOplusXi(2,5) = -1;
157     }
158 
159     bool read ( istream& in ) {}
160     bool write ( ostream& out ) const {}
161 protected:
162     Eigen::Vector3d _point;                     //設立誤差點 之后將其與測量值進行相減 求得誤差
163 };
164     #endif
165 
166 #endif
167 //自己設置的打印配置信息
168 void printConfigInfo(){
169     cout<<"This is the example from GaoXiang's book : ICP結果是第二幀到第一幀的RT."<<endl;
170 #if BAOptimizer
171 
172     cout<<"BA Optimizer is Provided!"<<endl;
173     #if ISBAProvideInitValue
174     cout<<"The RT from ICP's result is Provided for BA as a initialization."<<endl;
175     #else
176     cout<<" But,Not provide initialization for BA!"<<endl;
177     #endif
178 
179     #if  MyselfOptimizerMethod
180     cout<<"優化了空間點和位姿節點!"<<endl;
181     #else
182     cout<<"未對空間點進行優化!"<<endl;
183     #endif
184 
185 #endif
186 }
187 int main ( int argc, char** argv )
188 {
189     if ( argc != 5 )
190     {
191         cout<<"usage: pose_estimation_3d3d img1 img2 depth1 depth2"<<endl;
192         return 1;
193     }
194     printConfigInfo();//輸出配置信息
195     //-- 讀取圖像
196     Mat img_1 = imread ( argv[1], CV_LOAD_IMAGE_COLOR );
197     Mat img_2 = imread ( argv[2], CV_LOAD_IMAGE_COLOR );
198 
199     vector<KeyPoint> keypoints_1, keypoints_2;
200     vector<DMatch> matches;
201     find_feature_matches ( img_1, img_2, keypoints_1, keypoints_2, matches );
202     cout<<"一共找到了"<<matches.size() <<"組匹配點"<<endl;
203 
204     // 建立3D點
205     Mat depth1 = imread ( argv[3], CV_LOAD_IMAGE_UNCHANGED );       // 深度圖為16位無符號數,單通道圖像
206     Mat depth2 = imread ( argv[4], CV_LOAD_IMAGE_UNCHANGED );       // 深度圖為16位無符號數,單通道圖像
207     Mat K = ( Mat_<double> ( 3,3 ) << 520.9, 0, 325.1, 0, 521.0, 249.7, 0, 0, 1 );
208     vector<Point3f> pts1, pts2;
209 
210     for ( DMatch m:matches )
211     {
212         ushort d1 = depth1.ptr<unsigned short> ( int ( keypoints_1[m.queryIdx].pt.y ) ) [ int ( keypoints_1[m.queryIdx].pt.x ) ];
213         ushort d2 = depth2.ptr<unsigned short> ( int ( keypoints_2[m.trainIdx].pt.y ) ) [ int ( keypoints_2[m.trainIdx].pt.x ) ];
214         if ( d1==0 || d2==0 )   // bad depth
215             continue;
216         Point2d p1 = pixel2cam ( keypoints_1[m.queryIdx].pt, K );
217         Point2d p2 = pixel2cam ( keypoints_2[m.trainIdx].pt, K );
218         float dd1 = float ( d1 ) /5000.0;
219         float dd2 = float ( d2 ) /5000.0;
220 
221         //存儲特征點的3D坐標
222         pts1.push_back ( Point3f ( p1.x*dd1, p1.y*dd1, dd1 ) );
223         pts2.push_back ( Point3f ( p2.x*dd2, p2.y*dd2, dd2 ) );
224     }
225 
226     cout<<"3d-3d pairs: "<<pts1.size() <<endl;
227     Mat R, t;
228     pose_estimation_3d3d ( pts1, pts2, R, t );                      //ICP方式的位姿估計
229     cout<<"ICP via SVD results: "<<endl;
230     cout<<"R = "<<R<<endl;
231     cout<<"t = "<<t<<endl;
232    //實際上是第一幀到第二幀的R T
233     cout<<"第一幀到第二幀的旋轉和平移:" << endl << "R_inv = "<<R.t() <<endl;
234     cout<<"t_inv = "<<-R.t() *t<<endl;
235 
236     cout<<"calling bundle adjustment"<<endl;
237 
238 #if  BAOptimizer
239     bundleAdjustment( pts1, pts2, R, t );                          //BA優化估計相機位姿  RT 是提供優化的初始值
240 #endif
241 
242     // verify p1 = R*p2 + t
243 /*    for ( int i=0; i<5; i++ )
244     {
245         cout<<"p1 = "<<pts1[i]<<endl;
246         cout<<"p2 = "<<pts2[i]<<endl;
247         cout<<"(R*p2+t) = "<<
248             R * (Mat_<double>(3,1)<<pts2[i].x, pts2[i].y, pts2[i].z) + t
249             <<endl;
250         cout<<endl;
251     }
252   */
253 }
254 
255 void find_feature_matches ( const Mat& img_1, const Mat& img_2,
256                             std::vector<KeyPoint>& keypoints_1,
257                             std::vector<KeyPoint>& keypoints_2,
258                             std::vector< DMatch >& matches )
259 {
260     //-- 初始化
261     Mat descriptors_1, descriptors_2;
262     // used in OpenCV3
263     Ptr<FeatureDetector> detector = ORB::create();
264     Ptr<DescriptorExtractor> descriptor = ORB::create();
265     // use this if you are in OpenCV2
266     // Ptr<FeatureDetector> detector = FeatureDetector::create ( "ORB" );
267     // Ptr<DescriptorExtractor> descriptor = DescriptorExtractor::create ( "ORB" );
268     Ptr<DescriptorMatcher> matcher  = DescriptorMatcher::create("BruteForce-Hamming");
269     //-- 第一步:檢測 Oriented FAST 角點位置
270     detector->detect ( img_1,keypoints_1 );
271     detector->detect ( img_2,keypoints_2 );
272 
273     //-- 第二步:根據角點位置計算 BRIEF 描述子
274     descriptor->compute ( img_1, keypoints_1, descriptors_1 );
275     descriptor->compute ( img_2, keypoints_2, descriptors_2 );
276 
277     //-- 第三步:對兩幅圖像中的BRIEF描述子進行匹配,使用 Hamming 距離
278     vector<DMatch> match;
279    // BFMatcher matcher ( NORM_HAMMING );
280     matcher->match ( descriptors_1, descriptors_2, match );
281 
282     //-- 第四步:匹配點對篩選
283     double min_dist=10000, max_dist=0;
284 
285     //找出所有匹配之間的最小距離和最大距離, 即是最相似的和最不相似的兩組點之間的距離
286     for ( int i = 0; i < descriptors_1.rows; i++ )
287     {
288         double dist = match[i].distance;
289         if ( dist < min_dist ) min_dist = dist;
290         if ( dist > max_dist ) max_dist = dist;
291     }
292 
293     printf ( "-- Max dist : %f \n", max_dist );
294     printf ( "-- Min dist : %f \n", min_dist );
295 
296     //當描述子之間的距離大於兩倍的最小距離時,即認為匹配有誤.但有時候最小距離會非常小,設置一個經驗值30作為下限.
297     for ( int i = 0; i < descriptors_1.rows; i++ )
298     {
299         if ( match[i].distance <= max ( 2*min_dist, 30.0 ) )
300         {
301             matches.push_back ( match[i] );
302         }
303     }
304 }
305 
306 Point2d pixel2cam ( const Point2d& p, const Mat& K )
307 {
308     return Point2d
309            (
310                ( p.x - K.at<double> ( 0,2 ) ) / K.at<double> ( 0,0 ),
311                ( p.y - K.at<double> ( 1,2 ) ) / K.at<double> ( 1,1 )
312            );
313 }
314 
315 void pose_estimation_3d3d (
316     const vector<Point3f>& pts1,
317     const vector<Point3f>& pts2,
318     Mat& R, Mat& t
319 )
320 {
321     Point3f p1, p2;     // center of mass
322     int N = pts1.size();
323     for ( int i=0; i<N; i++ )
324     {
325         p1 += pts1[i];
326         p2 += pts2[i];
327     }
328     p1 = Point3f( Vec3f(p1) /  N);
329     p2 = Point3f( Vec3f(p2) / N);
330     vector<Point3f>     q1 ( N ), q2 ( N ); // remove the center 去質心坐標
331     for ( int i=0; i<N; i++ )
332     {
333         q1[i] = pts1[i] - p1;
334         q2[i] = pts2[i] - p2;
335     }
336 
337     // compute q1*q2^T
338     Eigen::Matrix3d W = Eigen::Matrix3d::Zero();
339     for ( int i=0; i<N; i++ )
340     {
341         W += Eigen::Vector3d ( q1[i].x, q1[i].y, q1[i].z ) * Eigen::Vector3d ( q2[i].x, q2[i].y, q2[i].z ).transpose();
342     }
343     cout<<"W="<<W<<endl;
344 
345     // SVD on W
346     Eigen::JacobiSVD<Eigen::Matrix3d> svd ( W, Eigen::ComputeFullU|Eigen::ComputeFullV );//因為知道矩陣W的類型 所以在分解的時候直接是FullU | FullV
347     Eigen::Matrix3d U = svd.matrixU();
348     Eigen::Matrix3d V = svd.matrixV();
349     cout<<"U="<<U<<endl;
350     cout<<"V="<<V<<endl;
351 
352     //例程本身的實現方式 求出的R T是第二幀到第一幀的
353     Eigen::Matrix3d R_ = U* ( V.transpose() );
354     Eigen::Vector3d t_ = Eigen::Vector3d ( p1.x, p1.y, p1.z ) - R_ * Eigen::Vector3d ( p2.x, p2.y, p2.z );
355 
356     // convert to cv::Mat
357     R = ( Mat_<double> ( 3,3 ) <<
358           R_ ( 0,0 ), R_ ( 0,1 ), R_ ( 0,2 ),
359           R_ ( 1,0 ), R_ ( 1,1 ), R_ ( 1,2 ),
360           R_ ( 2,0 ), R_ ( 2,1 ), R_ ( 2,2 )
361         );
362     t = ( Mat_<double> ( 3,1 ) << t_ ( 0,0 ), t_ ( 1,0 ), t_ ( 2,0 ) );
363 }
364 #if  BAOptimizer
365 void bundleAdjustment (
366     const vector< Point3f >& pts1,
367     const vector< Point3f >& pts2,
368     Mat& R, Mat& t )                //實際上 R t在這里並不是必要的 這個只是用來提供BA初始值
369 {
370     // 初始化g2o
371     typedef g2o::BlockSolver< g2o::BlockSolverTraits<6,3> > Block;  // pose維度為 6, landmark 維度為 3
372     std::unique_ptr<Block::LinearSolverType>linearSolver = g2o::make_unique<g2o::LinearSolverEigen<Block::PoseMatrixType>>();   //線性方程求解器
373     std::unique_ptr<Block>solver_ptr = g2o::make_unique<Block>( std::move(linearSolver) );                                      //矩陣塊求解器
374     g2o::OptimizationAlgorithmLevenberg * solver = new g2o::OptimizationAlgorithmLevenberg( std::move(solver_ptr) );            //LM法
375 
376 /*  //另一種修改錯誤的方式
377     Block::LinearSolverType* linearSolver = new g2o::LinearSolverEigen<Block::PoseMatrixType>();  // 線性方程求解器
378     Block* solver_ptr = new Block( std::unique_ptr<Block::LinearSolverType>(linearSolver) );      // 矩陣塊求解器
379     g2o::OptimizationAlgorithmLevenberg * solver = new g2o::OptimizationAlgorithmLevenberg ( std::unique_ptr <g2o::Solver>(solver_ptr) ); //LM法
380 */
381     g2o::SparseOptimizer optimizer;
382     optimizer.setAlgorithm( solver );
383 
384     // vertex   這里僅僅添加了第二幀節點
385     auto pose = new g2o::VertexSE3Expmap();                  // camera pose
386     pose->setId(0);                                          // 位姿節點編號為0
387 #if ISBAProvideInitValue                                     // 為圖優化提供ICP結果作為初值
388     Eigen::Matrix3d R_mat;
389     R_mat <<
390           R.at<double> ( 0,0 ), R.at<double> ( 0,1 ), R.at<double> ( 0,2 ),
391             R.at<double> ( 1,0 ), R.at<double> ( 1,1 ), R.at<double> ( 1,2 ),
392             R.at<double> ( 2,0 ), R.at<double> ( 2,1 ), R.at<double> ( 2,2 );
393     pose->setEstimate(  g2o::SE3Quat(
394             R_mat,
395             Eigen::Vector3d( t.at<double> ( 0,0 ),t.at<double> ( 0,1 ),t.at<double> ( 0,2 ) )
396                                     )
397                      );
398 #else                                                       // 提供默認初值
399     pose->setEstimate( g2o::SE3Quat(
400         Eigen::Matrix3d::Identity(),
401         Eigen::Vector3d( 0,0,0 )
402     ) );
403 #endif
404     optimizer.addVertex( pose );                            //向優化器中添加節點
405 #if MyselfOptimizerMethod                                   //添加空間節點  並且按照書上的方式進行優化的
406     int pointIndex = 1;                                     //因為上面的位姿節點就1個  所以我們這里標號為1
407     for( auto &p: pts2 ){
408         auto point = new g2o::VertexSBAPointXYZ();
409         point->setId( pointIndex++ );
410         point->setMarginalized( true );                     //設置邊緣化(必須設置 否則出錯)
411         point->setEstimate( Eigen::Vector3d( p.x, p.y, p.z ) );
412         optimizer.addVertex( point );
413     }
414 #endif
415     // edges
416     int index = 0;
417     vector<EdgeProjectXYZRGBDPoseOnly*> edges;
418     for ( size_t i=0; i<pts1.size(); i++ )
419     {
420 #if MyselfOptimizerMethod
421         auto edge = new EdgeProjectXYZRGBDPoseOnly( );      //在課后習題中修改的EdgeProjectXYZRGBDPoseOnly可以去掉_point成員變量
422 #else
423         auto edge = new EdgeProjectXYZRGBDPoseOnly(
424                 Eigen::Vector3d(pts2[i].x, pts2[i].y, pts2[i].z) );
425 #endif
426         edge->setId( index );
427 #if  MyselfOptimizerMethod
428         edge->setVertex( 0 , dynamic_cast< g2o::VertexSBAPointXYZ *> ( optimizer.vertex(index)) );
429         edge->setVertex( 1 , dynamic_cast< g2o::OptimizableGraph::Vertex *> ( optimizer.vertex(0) ) );
430 #else   //參考ORB_SLAM:這里將原來的g2o::VertexSE3Expmap* 替換為g2o::OptimizableGraph::Vertex *
431         edge->setVertex( 0 , dynamic_cast< g2o::OptimizableGraph::Vertex *> ( optimizer.vertex(0) ) );
432 #endif
433         //這里以第一幀為測量值 說明優化的是第二幀到第一幀的旋轉r和平移t
434         edge->setMeasurement( Eigen::Vector3d (
435                 pts1[i].x, pts1[i].y, pts1[i].z)
436                             );
437         edge->setInformation( Eigen::Matrix3d::Identity()*1e4 );
438         optimizer.addEdge(edge);                            //向優化器中添加邊
439         index++;
440         edges.push_back(edge);                              //存儲邊指針
441     }
442 
443     chrono::steady_clock::time_point t1 = chrono::steady_clock::now();
444     optimizer.setVerbose( true );
445     optimizer.initializeOptimization();
446     optimizer.optimize(100);
447     chrono::steady_clock::time_point t2 = chrono::steady_clock::now();
448     chrono::duration<double> time_used = chrono::duration_cast<chrono::duration<double>>(t2-t1);
449     cout<<"optimization costs time: "<<time_used.count()<<" seconds."<<endl;
450 
451     cout<<endl<<"after optimization:"<<endl;
452     cout<<"T="<<endl<<Eigen::Isometry3d( pose->estimate() ).matrix()<<endl;
453 /*
454     cout<<"輸出優化后的point值:"<<endl;
455     for (int j = 0; j <3 ; ++j) {
456         cout<< dynamic_cast< g2o::VertexSBAPointXYZ * > ( optimizer.vertex(j+1) )->estimate()<<endl<<endl;//Eigen::Vector3d
457     }
458     cout<<endl<<"優化前的點:"<<endl;
459     for (int i = 0; i <3 ; ++i) {
460         cout<<pts2[i]<<endl<<endl;
461     }
462 */
463 
464 }
465 #endif

運行結果截圖:

參考資料:
視覺slam十四講從理論到實踐

 

歡迎大家關注我的微信公眾號「佛系師兄」,里面有關於 Ceres 以及 OpenCV 等更多技術文章。

比如

反復研究好幾遍,我才發現關於 CMake 變量還可以這樣理解!

更多好的文章會優先在里面不定期分享!打開微信客戶端,掃描下方二維碼即可關注!


免責聲明!

本站轉載的文章為個人學習借鑒使用,本站對版權不負任何法律責任。如果侵犯了您的隱私權益,請聯系本站郵箱yoyou2525@163.com刪除。



 
粵ICP備18138465號   © 2018-2025 CODEPRJ.COM