# Viewer.cpp ### Viewer::Viewer() Viewer的參數初始化 在[System::System()](#System::System())中引用 #### 定義 ``` Viewer::Viewer(System* pSystem, FrameDrawer *pFrameDrawer, MapDrawer *pMapDrawer, Tracking *pTracking, const string &strSettingPath): mpSystem(pSystem), mpFrameDrawer(pFrameDrawer), mpMapDrawer(pMapDrawer), mpTracker(pTracking), mbFinishRequested(false), mbFinished(true), mbStopped(false), mbStopRequested(false) ``` #### 函式流程 1. 讀取配置檔案 2. 參數初始化 #### 流程詳解 1. 讀取配置檔案 ``` cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ); ``` 2. 參數初始化 ``` float fps = fSettings["Camera.fps"]; if(fps<1) fps=30; mT = 1e3/fps; mImageWidth = fSettings["Camera.width"]; mImageHeight = fSettings["Camera.height"]; if(mImageWidth<1 || mImageHeight<1) { mImageWidth = 640; mImageHeight = 480; } mViewpointX = fSettings["Viewer.ViewpointX"]; mViewpointY = fSettings["Viewer.ViewpointY"]; mViewpointZ = fSettings["Viewer.ViewpointZ"]; mViewpointF = fSettings["Viewer.ViewpointF"]; ``` ### Viewer::Run() 跑可視化界面線程 在[System::System()](#System::System())中引用 #### 函式流程 1. 可視化界面初始化 2. 建立可視化界面選單 3. 建立虛擬相機 4. 定義可視化界面面板 5. 線程開始 6. 得到最新的相機姿態 7. 根據相機姿態調整視角 8. 繪製當前相機 9. 繪製當前關鍵幀 10. 繪製當前地圖點 11. 顯示有特徵點的影像 12. 當reset按下時,重設系統 13. 停止系統 #### 流程詳解 1. 可視化界面初始化 ``` //這個變數配合 SetFinish 函數用於指示該函數是否執行完畢 mbFinished = false; pangolin::CreateWindowAndBind("ORB-SLAM2: Map Viewer",1024,768); // 3D Mouse handler requires depth testing to be enabled // 啟動深度測試,OpenGL只繪製最前面的一層,繪製時檢查當前像素前面是否有別的像素,如果別的像素擋住了它,那它就不會繪製 glEnable(GL_DEPTH_TEST); // Issue specific OpenGl we might need // 在OpenGL中使用顏色混合 glEnable(GL_BLEND); // 選擇混合選項 glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); ``` 2. 建立可視化界面選單 ``` // 新建按鈕和選擇框,第一個參數為按鈕的名字,第二個為默認狀態,第三個為是否有選擇框 pangolin::CreatePanel("menu").SetBounds(0.0,1.0,0.0,pangolin::Attach::Pix(175)); pangolin::Var<bool> menuFollowCamera("menu.Follow Camera",true,true); pangolin::Var<bool> menuShowPoints("menu.Show Points",true,true); pangolin::Var<bool> menuShowKeyFrames("menu.Show KeyFrames",true,true); pangolin::Var<bool> menuShowGraph("menu.Show Graph",true,true); pangolin::Var<bool> menuLocalizationMode("menu.Localization Mode",false,true); pangolin::Var<bool> menuReset("menu.Reset",false,false); ``` 3. 建立虛擬相機 ``` // Define Camera Render Object (for view / scene browsing) // 定義相機投影模型:ProjectionMatrix(w, h, fu, fv, u0, v0, zNear, zFar) // 定義觀測方位向量:觀測點位置:(mViewpointX mViewpointY mViewpointZ) // 觀測目標位置:(0, 0, 0) // 觀測的方位向量:(0.0,-1.0, 0.0) pangolin::OpenGlRenderState s_cam( pangolin::ProjectionMatrix(1024,768,mViewpointF,mViewpointF,512,389,0.1,1000), pangolin::ModelViewLookAt(mViewpointX,mViewpointY,mViewpointZ, 0,0,0,0.0,-1.0, 0.0) ); ``` 4. 定義可視化界面面板 ``` // Add named OpenGL viewport to window and provide 3D Handler // 定義顯示面板大小,orbslam中有左右兩個面板,昨天顯示一些按鈕,右邊顯示圖形 // 前兩個參數(0.0, 1.0)表明寬度和麵板縱向寬度和窗口大小相同 // 中間兩個參數(pangolin::Attach::Pix(175), 1.0)表明右邊所有部分用於顯示圖形 // 最後一個參數(-1024.0f/768.0f)為顯示長寬比 pangolin::View& d_cam = pangolin::CreateDisplay() .SetBounds(0.0, 1.0, pangolin::Attach::Pix(175), 1.0, -1024.0f/768.0f) .SetHandler(new pangolin::Handler3D(s_cam)); ``` 5. 線程開始 ``` pangolin::OpenGlMatrix Twc; Twc.SetIdentity(); cv::namedWindow("ORB-SLAM2: Current Frame"); bool bFollow = true; bool bLocalizationMode = false; while(1) { // 清除緩衝區中的當前可寫的顏色緩衝 和 深度緩衝 glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); ``` 6. 得到最新的相機姿態 ``` mpMapDrawer->GetCurrentOpenGLCameraMatrix(Twc); ``` 跳到[MapDrawer::GetCurrentOpenGLCameraMatrix()](#MapDrawer::GetCurrentOpenGLCameraMatrix()) 7. 根據相機姿態調整視角 ``` // menuFollowCamera為按鈕的狀態,bFollow為真實的狀態 //相機正在跟隨 if(menuFollowCamera && bFollow) { // 相機跟隨Twc位置的設置 s_cam.Follow(Twc); } //相機剛剛啟動跟隨 else if(menuFollowCamera && !bFollow) { //確保在啟用相機跟隨功能時,相機的視角能夠根據使用者指定的位置和朝向進行調整。 s_cam.SetModelViewMatrix(pangolin::ModelViewLookAt(mViewpointX,mViewpointY,mViewpointZ, 0,0,0,0.0,-1.0, 0.0)); s_cam.Follow(Twc); bFollow = true; } //相機不進行跟隨 else if(!menuFollowCamera && bFollow) { bFollow = false; } if(menuLocalizationMode && !bLocalizationMode) { //打開定位模式 mpSystem->ActivateLocalizationMode(); bLocalizationMode = true; } else if(!menuLocalizationMode && bLocalizationMode) { //關閉定位模式 mpSystem->DeactivateLocalizationMode(); bLocalizationMode = false; } d_cam.Activate(s_cam); // 設置為白色,glClearColor(red, green, blue, alpha),數值範圍(0, 1) glClearColor(1.0f,1.0f,1.0f,1.0f); ``` 8. 繪製當前相機 ``` //繪製當前相機 mpMapDrawer->DrawCurrentCamera(Twc); ``` mpMapDrawer->DrawCurrentCamera: 跳到[MapDrawer::DrawCurrentCamera()](#MapDrawer::DrawCurrentCamera()) 9. 繪製當前關鍵幀 ``` if(menuShowKeyFrames || menuShowGraph) mpMapDrawer->DrawKeyFrames(menuShowKeyFrames,menuShowGraph); ``` 跳到[MapDrawer::DrawKeyFrames()](#MapDrawer::DrawKeyFrames()) 10. 繪製當前地圖點 ``` if(menuShowPoints) mpMapDrawer->DrawMapPoints(); //刷新視窗 pangolin::FinishFrame(); ``` 跳到[MapDrawer::DrawMapPoints()](#MapDrawer::DrawMapPoints()) 11. 繪製有特徵點的影像 ``` cv::Mat im = mpFrameDrawer->DrawFrame(); cv::imshow("ORB-SLAM2: Current Frame",im); cv::waitKey(mT); ``` 跳到[FrameDrawer::DrawFrame()](#FrameDrawer::DrawFrame()) 12. 當reset按下時,重設系統 ``` //reset按鈕是否有被按下 if(menuReset) { menuShowGraph = true; menuShowKeyFrames = true; menuShowPoints = true; menuLocalizationMode = false; if(bLocalizationMode) mpSystem->DeactivateLocalizationMode(); bLocalizationMode = false; bFollow = true; menuFollowCamera = true; mpSystem->Reset(); menuReset = false; } ``` 13. 停止系統 ``` if(Stop()) { while(isStopped()) { //usleep(3000); std::this_thread::sleep_for(std::chrono::milliseconds(3)); } } if(CheckFinish()) break; } SetFinish(); ```