第七講 添加回環檢測
2016.11 更新
- 把原文的SIFT替換成了ORB,這樣你可以在沒有nonfree模塊下使用本程序了。
- 回環檢測的閾值作出了相應的調整。
- 請以現在的github上源碼為准。
簡單回環檢測的流程
上一講中,我們介紹了圖優化軟件g2o的使用。本講,我們將實現一個簡單的回環檢測程序,利用g2o提升slam軌跡與地圖的質量。本講結束后,讀者朋友們將得到一個完整的slam程序,可以跑通我們在百度雲上給出的數據了。所以呢,本講也將成為我們“一起做”系列的終點啦。
小蘿卜:這么快就要結束了嗎師兄?
師兄:嗯,因為我想要說的都教給大家了嘛。不過,盡管如此,這個教程的程序還是比較初步的,可以進一步進行效率、魯棒性方面的優化,這就要靠大家后續的努力啦。同時我的暑假也將近結束,要開始新一輪的工作了呢。
好的,話不多說,先來講講,上一講的程序離完整的slam還有哪些距離。主要說來有兩點:
- 關鍵幀的提取。把每一幀都拼到地圖是去是不明智的。因為幀與幀之間距離很近,導致地圖需要頻繁更新,浪費時間與空間。所以,我們希望,當機器人的運動超過一定間隔,就增加一個“關鍵幀”。最后只需把關鍵幀拼到地圖里就行了。
- 回環的檢測。回環的本質是識別曾經到過的地方。最簡單的回環檢測策略,就是把新來的關鍵幀與之前所有的關鍵幀進行比較,不過這樣會導致越往后,需要比較的幀越多。所以,稍微快速一點的方法是在過去的幀里隨機挑選一些,與之進行比較。更進一步的,也可以用圖像處理/模式識別的方法計算圖像間的相似性,對相似的圖像進行檢測。
把這兩者合在一起,就得到了我們slam程序的基本流程。以下為偽碼:
- 初始化關鍵幀序列:$F$,並將第一幀$f_0$放入$F$。
- 對於新來的一幀$I$,計算$F$中最后一幀與$I$的運動,並估計該運動的大小$e$。有以下幾種可能性:
- 若$e>E_{error}$,說明運動太大,可能是計算錯誤,丟棄該幀;
- 若沒有匹配上(match太少),說明該幀圖像質量不高,丟棄;
- 若$e<E_{key}$,說明離前一個關鍵幀很近,同樣丟棄;
- 剩下的情況,只有是特征匹配成功,運動估計正確,同時又離上一個關鍵幀有一定距離,則把$I$作為新的關鍵幀,進入回環檢測程序:
- 近距離回環:匹配$I$與$F$末尾$m$個關鍵幀。匹配成功時,在圖里增加一條邊。
- 隨機回環:隨機在$F$里取$n$個幀,與$I$進行匹配。若匹配上,在圖里增加一條邊。
- 將$I$放入$F$末尾。若有新的數據,則回2; 若無,則進行優化與地圖拼接。
小蘿卜:slam流程都是這樣的嗎?
師兄:大體上如此,也可以作一些更改。例如在線跑的話呢,可以定時進行一次優化與拼圖。或者,在成功檢測到回環時,同時檢測這兩個幀附近的幀,那樣得到的邊就更多啦。再有呢,如果要做實用的程序,還要考慮機器人如何運動,如果跟丟了怎么進行恢復等一些實際的問題呢。
實現代碼
代碼依舊是在上一講的代碼上進行更改得來的。由於是完整的程序,稍微有些長,請大家慢慢看:
src/slam.cpp
1 /************************************************************************* 2 > File Name: rgbd-slam-tutorial-gx/part V/src/visualOdometry.cpp 3 > Author: xiang gao 4 > Mail: gaoxiang12@mails.tsinghua.edu.cn 5 > Created Time: 2015年08月15日 星期六 15時35分42秒 6 * add g2o slam end to visual odometry 7 * add keyframe and simple loop closure 8 ************************************************************************/ 9 10 #include <iostream> 11 #include <fstream> 12 #include <sstream> 13 using namespace std; 14 15 #include "slamBase.h" 16 17 #include <pcl/filters/voxel_grid.h> 18 #include <pcl/filters/passthrough.h> 19 20 #include <g2o/types/slam3d/types_slam3d.h> 21 #include <g2o/core/sparse_optimizer.h> 22 #include <g2o/core/block_solver.h> 23 #include <g2o/core/factory.h> 24 #include <g2o/core/optimization_algorithm_factory.h> 25 #include <g2o/core/optimization_algorithm_gauss_newton.h> 26 #include <g2o/solvers/csparse/linear_solver_csparse.h> 27 #include <g2o/core/robust_kernel.h> 28 #include <g2o/core/robust_kernel_factory.h> 29 #include <g2o/core/optimization_algorithm_levenberg.h> 30 31 // 把g2o的定義放到前面 32 typedef g2o::BlockSolver_6_3 SlamBlockSolver; 33 typedef g2o::LinearSolverCSparse< SlamBlockSolver::PoseMatrixType > SlamLinearSolver; 34 35 // 給定index,讀取一幀數據 36 FRAME readFrame( int index, ParameterReader& pd ); 37 // 估計一個運動的大小 38 double normofTransform( cv::Mat rvec, cv::Mat tvec ); 39 40 // 檢測兩個幀,結果定義 41 enum CHECK_RESULT {NOT_MATCHED=0, TOO_FAR_AWAY, TOO_CLOSE, KEYFRAME}; 42 // 函數聲明 43 CHECK_RESULT checkKeyframes( FRAME& f1, FRAME& f2, g2o::SparseOptimizer& opti, bool is_loops=false ); 44 // 檢測近距離的回環 45 void checkNearbyLoops( vector<FRAME>& frames, FRAME& currFrame, g2o::SparseOptimizer& opti ); 46 // 隨機檢測回環 47 void checkRandomLoops( vector<FRAME>& frames, FRAME& currFrame, g2o::SparseOptimizer& opti ); 48 49 int main( int argc, char** argv ) 50 { 51 // 前面部分和vo是一樣的 52 ParameterReader pd; 53 int startIndex = atoi( pd.getData( "start_index" ).c_str() ); 54 int endIndex = atoi( pd.getData( "end_index" ).c_str() ); 55 56 // 所有的關鍵幀都放在了這里 57 vector< FRAME > keyframes; 58 // initialize 59 cout<<"Initializing ..."<<endl; 60 int currIndex = startIndex; // 當前索引為currIndex 61 FRAME currFrame = readFrame( currIndex, pd ); // 當前幀數據 62 63 string detector = pd.getData( "detector" ); 64 string descriptor = pd.getData( "descriptor" ); 65 CAMERA_INTRINSIC_PARAMETERS camera = getDefaultCamera(); 66 computeKeyPointsAndDesp( currFrame, detector, descriptor ); 67 PointCloud::Ptr cloud = image2PointCloud( currFrame.rgb, currFrame.depth, camera ); 68 69 /******************************* 70 // 新增:有關g2o的初始化 71 *******************************/ 72 // 初始化求解器 73 SlamLinearSolver* linearSolver = new SlamLinearSolver(); 74 linearSolver->setBlockOrdering( false ); 75 SlamBlockSolver* blockSolver = new SlamBlockSolver( linearSolver ); 76 g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg( blockSolver ); 77 78 g2o::SparseOptimizer globalOptimizer; // 最后用的就是這個東東 79 globalOptimizer.setAlgorithm( solver ); 80 // 不要輸出調試信息 81 globalOptimizer.setVerbose( false ); 82 83 84 // 向globalOptimizer增加第一個頂點 85 g2o::VertexSE3* v = new g2o::VertexSE3(); 86 v->setId( currIndex ); 87 v->setEstimate( Eigen::Isometry3d::Identity() ); //估計為單位矩陣 88 v->setFixed( true ); //第一個頂點固定,不用優化 89 globalOptimizer.addVertex( v ); 90 91 keyframes.push_back( currFrame ); 92 93 double keyframe_threshold = atof( pd.getData("keyframe_threshold").c_str() ); 94 95 bool check_loop_closure = pd.getData("check_loop_closure")==string("yes"); 96 for ( currIndex=startIndex+1; currIndex<endIndex; currIndex++ ) 97 { 98 cout<<"Reading files "<<currIndex<<endl; 99 FRAME currFrame = readFrame( currIndex,pd ); // 讀取currFrame 100 computeKeyPointsAndDesp( currFrame, detector, descriptor ); //提取特征 101 CHECK_RESULT result = checkKeyframes( keyframes.back(), currFrame, globalOptimizer ); //匹配該幀與keyframes里最后一幀 102 switch (result) // 根據匹配結果不同采取不同策略 103 { 104 case NOT_MATCHED: 105 //沒匹配上,直接跳過 106 cout<<RED"Not enough inliers."<<endl; 107 break; 108 case TOO_FAR_AWAY: 109 // 太近了,也直接跳 110 cout<<RED"Too far away, may be an error."<<endl; 111 break; 112 case TOO_CLOSE: 113 // 太遠了,可能出錯了 114 cout<<RESET"Too close, not a keyframe"<<endl; 115 break; 116 case KEYFRAME: 117 cout<<GREEN"This is a new keyframe"<<endl; 118 // 不遠不近,剛好 119 /** 120 * This is important!! 121 * This is important!! 122 * This is important!! 123 * (very important so I've said three times!) 124 */ 125 // 檢測回環 126 if (check_loop_closure) 127 { 128 checkNearbyLoops( keyframes, currFrame, globalOptimizer ); 129 checkRandomLoops( keyframes, currFrame, globalOptimizer ); 130 } 131 keyframes.push_back( currFrame ); 132 break; 133 default: 134 break; 135 } 136 137 } 138 139 // 優化 140 cout<<RESET"optimizing pose graph, vertices: "<<globalOptimizer.vertices().size()<<endl; 141 globalOptimizer.save("./data/result_before.g2o"); 142 globalOptimizer.initializeOptimization(); 143 globalOptimizer.optimize( 100 ); //可以指定優化步數 144 globalOptimizer.save( "./data/result_after.g2o" ); 145 cout<<"Optimization done."<<endl; 146 147 // 拼接點雲地圖 148 cout<<"saving the point cloud map..."<<endl; 149 PointCloud::Ptr output ( new PointCloud() ); //全局地圖 150 PointCloud::Ptr tmp ( new PointCloud() ); 151 152 pcl::VoxelGrid<PointT> voxel; // 網格濾波器,調整地圖分辨率 153 pcl::PassThrough<PointT> pass; // z方向區間濾波器,由於rgbd相機的有效深度區間有限,把太遠的去掉 154 pass.setFilterFieldName("z"); 155 pass.setFilterLimits( 0.0, 4.0 ); //4m以上就不要了 156 157 double gridsize = atof( pd.getData( "voxel_grid" ).c_str() ); //分辨圖可以在parameters.txt里調 158 voxel.setLeafSize( gridsize, gridsize, gridsize ); 159 160 for (size_t i=0; i<keyframes.size(); i++) 161 { 162 // 從g2o里取出一幀 163 g2o::VertexSE3* vertex = dynamic_cast<g2o::VertexSE3*>(globalOptimizer.vertex( keyframes[i].frameID )); 164 Eigen::Isometry3d pose = vertex->estimate(); //該幀優化后的位姿 165 PointCloud::Ptr newCloud = image2PointCloud( keyframes[i].rgb, keyframes[i].depth, camera ); //轉成點雲 166 // 以下是濾波 167 voxel.setInputCloud( newCloud ); 168 voxel.filter( *tmp ); 169 pass.setInputCloud( tmp ); 170 pass.filter( *newCloud ); 171 // 把點雲變換后加入全局地圖中 172 pcl::transformPointCloud( *newCloud, *tmp, pose.matrix() ); 173 *output += *tmp; 174 tmp->clear(); 175 newCloud->clear(); 176 } 177 178 voxel.setInputCloud( output ); 179 voxel.filter( *tmp ); 180 //存儲 181 pcl::io::savePCDFile( "./data/result.pcd", *tmp ); 182 183 cout<<"Final map is saved."<<endl; 184 globalOptimizer.clear(); 185 186 return 0; 187 } 188 189 FRAME readFrame( int index, ParameterReader& pd ) 190 { 191 FRAME f; 192 string rgbDir = pd.getData("rgb_dir"); 193 string depthDir = pd.getData("depth_dir"); 194 195 string rgbExt = pd.getData("rgb_extension"); 196 string depthExt = pd.getData("depth_extension"); 197 198 stringstream ss; 199 ss<<rgbDir<<index<<rgbExt; 200 string filename; 201 ss>>filename; 202 f.rgb = cv::imread( filename ); 203 204 ss.clear(); 205 filename.clear(); 206 ss<<depthDir<<index<<depthExt; 207 ss>>filename; 208 209 f.depth = cv::imread( filename, -1 ); 210 f.frameID = index; 211 return f; 212 } 213 214 double normofTransform( cv::Mat rvec, cv::Mat tvec ) 215 { 216 return fabs(min(cv::norm(rvec), 2*M_PI-cv::norm(rvec)))+ fabs(cv::norm(tvec)); 217 } 218 219 CHECK_RESULT checkKeyframes( FRAME& f1, FRAME& f2, g2o::SparseOptimizer& opti, bool is_loops) 220 { 221 static ParameterReader pd; 222 static int min_inliers = atoi( pd.getData("min_inliers").c_str() ); 223 static double max_norm = atof( pd.getData("max_norm").c_str() ); 224 static double keyframe_threshold = atof( pd.getData("keyframe_threshold").c_str() ); 225 static double max_norm_lp = atof( pd.getData("max_norm_lp").c_str() ); 226 static CAMERA_INTRINSIC_PARAMETERS camera = getDefaultCamera(); 227 static g2o::RobustKernel* robustKernel = g2o::RobustKernelFactory::instance()->construct( "Cauchy" ); 228 // 比較f1 和 f2 229 RESULT_OF_PNP result = estimateMotion( f1, f2, camera ); 230 if ( result.inliers < min_inliers ) //inliers不夠,放棄該幀 231 return NOT_MATCHED; 232 // 計算運動范圍是否太大 233 double norm = normofTransform(result.rvec, result.tvec); 234 if ( is_loops == false ) 235 { 236 if ( norm >= max_norm ) 237 return TOO_FAR_AWAY; // too far away, may be error 238 } 239 else 240 { 241 if ( norm >= max_norm_lp) 242 return TOO_FAR_AWAY; 243 } 244 245 if ( norm <= keyframe_threshold ) 246 return TOO_CLOSE; // too adjacent frame 247 // 向g2o中增加這個頂點與上一幀聯系的邊 248 // 頂點部分 249 // 頂點只需設定id即可 250 if (is_loops == false) 251 { 252 g2o::VertexSE3 *v = new g2o::VertexSE3(); 253 v->setId( f2.frameID ); 254 v->setEstimate( Eigen::Isometry3d::Identity() ); 255 opti.addVertex(v); 256 } 257 // 邊部分 258 g2o::EdgeSE3* edge = new g2o::EdgeSE3(); 259 // 連接此邊的兩個頂點id 260 edge->vertices() [0] = opti.vertex( f1.frameID ); 261 edge->vertices() [1] = opti.vertex( f2.frameID ); 262 edge->setRobustKernel( robustKernel ); 263 // 信息矩陣 264 Eigen::Matrix<double, 6, 6> information = Eigen::Matrix< double, 6,6 >::Identity(); 265 // 信息矩陣是協方差矩陣的逆,表示我們對邊的精度的預先估計 266 // 因為pose為6D的,信息矩陣是6*6的陣,假設位置和角度的估計精度均為0.1且互相獨立 267 // 那么協方差則為對角為0.01的矩陣,信息陣則為100的矩陣 268 information(0,0) = information(1,1) = information(2,2) = 100; 269 information(3,3) = information(4,4) = information(5,5) = 100; 270 // 也可以將角度設大一些,表示對角度的估計更加准確 271 edge->setInformation( information ); 272 // 邊的估計即是pnp求解之結果 273 Eigen::Isometry3d T = cvMat2Eigen( result.rvec, result.tvec ); 274 edge->setMeasurement( T.inverse() ); 275 // 將此邊加入圖中 276 opti.addEdge(edge); 277 return KEYFRAME; 278 } 279 280 void checkNearbyLoops( vector<FRAME>& frames, FRAME& currFrame, g2o::SparseOptimizer& opti ) 281 { 282 static ParameterReader pd; 283 static int nearby_loops = atoi( pd.getData("nearby_loops").c_str() ); 284 285 // 就是把currFrame和 frames里末尾幾個測一遍 286 if ( frames.size() <= nearby_loops ) 287 { 288 // no enough keyframes, check everyone 289 for (size_t i=0; i<frames.size(); i++) 290 { 291 checkKeyframes( frames[i], currFrame, opti, true ); 292 } 293 } 294 else 295 { 296 // check the nearest ones 297 for (size_t i = frames.size()-nearby_loops; i<frames.size(); i++) 298 { 299 checkKeyframes( frames[i], currFrame, opti, true ); 300 } 301 } 302 } 303 304 void checkRandomLoops( vector<FRAME>& frames, FRAME& currFrame, g2o::SparseOptimizer& opti ) 305 { 306 static ParameterReader pd; 307 static int random_loops = atoi( pd.getData("random_loops").c_str() ); 308 srand( (unsigned int) time(NULL) ); 309 // 隨機取一些幀進行檢測 310 311 if ( frames.size() <= random_loops ) 312 { 313 // no enough keyframes, check everyone 314 for (size_t i=0; i<frames.size(); i++) 315 { 316 checkKeyframes( frames[i], currFrame, opti, true ); 317 } 318 } 319 else 320 { 321 // randomly check loops 322 for (int i=0; i<random_loops; i++) 323 { 324 int index = rand()%frames.size(); 325 checkKeyframes( frames[index], currFrame, opti, true ); 326 } 327 } 328 }
幾點注解:
- 回環檢測是很怕"false positive"的,即“將實際上不同的地方當成了同一處”,這會導致地圖出現明顯的不一致。所以,在使用g2o時,要在邊里添加"robust kernel",保證一兩個錯誤的邊不會影響整體結果。
- 我在slambase.h里添加了一些彩色輸出代碼。運行此程序時,出現綠色信息則是添加新的關鍵幀,紅色為出錯。
parameters.txt里定義了檢測回環的一些參數:
#part 7 keyframe_threshold=0.1 max_norm_lp=5.0 # Loop closure check_loop_closure=yes nearby_loops=5 random_loops=5
其中,nearby_loops就是$m$,random_loops就是$n$啦。這兩個數如果設大一些,匹配的幀就會多,不過太大了就會影響整體速度了呢。
回環檢測的效果
對代碼進行編譯,然后bin/slam即可看到程序運行啦。
添加了回環檢測之后呢,g2o文件就不會像上次那樣孤零零的啦,看起來是這樣子的:
怎么樣?是不是感覺整條軌跡“如絲般順滑”了呢?它不再是上一講那樣一根筋通到底,而是有很多幀間的匹配數據,保證了一兩幀出錯能被其他匹配數據給“拉回來”。
百度雲上的數據最后拼出來是這樣的哦(780幀,關鍵幀62張,幀率5Hz左右):
咖啡台左側有明顯的人通過的痕跡,導致地圖上出現了他的身影(帥哥你好拉風):
嗯,這個就可以算作是基本的地圖啦。至此,slam的兩大目標:“軌跡”和“地圖”我們都已得到了,可以算是基本上解決了這個問題了。
一些后話
這一個“一起做rgb-d slam”系列,前前后后花了我一個多月的時間。寫代碼,調代碼,然后寫成博文。雖然講的比較啰嗦,總體上希望能對各位slam愛好者、研究者有幫助啦!這樣我既然辛苦也很開心的!
寫作期間,得到了女朋友大臉蓮的不少幫助,也得到了讀者和同行之間的鼓勵,謝謝各位啦!等有工夫,我會把這一堆東西整理成一個pdf供slam初學者進行研究學習的。
slam仍是一個開放的問題,盡管有人曾說“在slam領域發文章越來越難”,然而現在機器人幾大期刊和會議(IJRR/TRO/RAM/JFD/ICRA/IROS...)仍有不少slam方面的文章。雖然我們“獲取軌跡與地圖”的目標已基本實現,但仍有許多工作等我們去做,包括:
- 更好的數學模型(新的濾波器/圖優化理論);
- 新的視覺特征/不使用特征的直接方法;
- 動態物體/人的處理;
- 地圖描述/點雲地圖優化/語義地圖
- 長時間/大規模/自動化slam
- 等等……
總之,大家千萬別以為“slam問題已經有標准答案啦”。等我對slam有新的理解時,也會寫新的博客為大家介紹的!
如果你覺得我的博客有幫助,可以進行幾塊錢的小額贊助,幫助我把博客寫得更好。(雖然我也是從別處學來的這招……)
本講代碼:https://github.com/gaoxiang12/rgbd-slam-tutorial-gx/tree/master/part%20VII
數據:http://yun.baidu.com/s/1i33uvw5
交流群:374238181