ORB_SLAM2原理及代码解析:Viewer 线程——Viewer::Run()
目录
1 作用及运行流程
2 参数及含义
3 代码
4 解析
4.1 初始化变量
4.2 创建Pangolin窗口与OpenGL环境
4.3 创建交互菜单面板
4.4 设置虚拟相机参数
4.5 创建可视化窗口
4.6 OpenGL矩阵与窗口初始化
4.7 主循环
4.8 设置结束标志
1 作用及运行流程
(1)初始可视化窗口;
(2)创建交互菜单;
(3)实时绘制当前地图、关键帧、相机;
(4)处理用户交互(重置、跟随、定位模式等);
(5)检查线程停止或结束信号。
2 参数及含义
3 代码
void Viewer::Run() {mbFinished = false;mbStopped = false;pangolin::CreateWindowAndBind("ORB-SLAM2: Map Viewer",1024,768);// 3D Mouse handler requires depth testing to be enabledglEnable(GL_DEPTH_TEST);// Issue specific OpenGl we might needglEnable (GL_BLEND);glBlendFunc (GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);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);// Define Camera Render Object (for view / scene browsing)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));// Add named OpenGL viewport to window and provide 3D Handlerpangolin::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));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);mpMapDrawer->GetCurrentOpenGLCameraMatrix(Twc);if(menuFollowCamera && bFollow){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(1.0f,1.0f,1.0f,1.0f);mpMapDrawer->DrawCurrentCamera(Twc);if(menuShowKeyFrames || menuShowGraph)mpMapDrawer->DrawKeyFrames(menuShowKeyFrames,menuShowGraph);if(menuShowPoints)mpMapDrawer->DrawMapPoints();pangolin::FinishFrame();cv::Mat im = mpFrameDrawer->DrawFrame();cv::imshow("ORB-SLAM2: Current Frame",im);cv::waitKey(mT);if(menuReset){menuShowGraph = true;menuShowKeyFrames = true;menuShowPoints = true;menuLocalizationMode = false;if(bLocalizationMode)mpSystem->DeactivateLocalizationMode();bLocalizationMode = false;bFollow = true;menuFollowCamera = true;mpSystem->Reset();menuReset = false;}if(Stop()){while(isStopped()){std::this_thread::sleep_for(std::chrono::microseconds(3000));}}if(CheckFinish())break;}SetFinish(); }
4 解析
4.1 初始化变量
mbFinished = false;mbStopped = false;
4.2 创建Pangolin窗口与OpenGL环境
pangolin::CreateWindowAndBind("ORB-SLAM2: Map Viewer",1024,768);// 3D Mouse handler requires depth testing to be enabled//功能:启用 OpenGL 的深度缓冲区(Z-Buffer)。这样在绘制 3D 地图点、相机、关键帧时,//OpenGL 会根据物体的深度自动判断遮挡关系。glEnable(GL_DEPTH_TEST);// Issue specific OpenGl we might need//允许绘制半透明对象或带透明度的 UI 元素。//例如,在 ORB-SLAM2 中绘制轨迹线或相机轮廓时,混合能让边缘柔和、不突兀。glEnable (GL_BLEND);glBlendFunc (GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
4.3 创建交互菜单面板
//创建名为"menu"的菜单面板,面板位置(下,上,左,右) 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);
4.4 设置虚拟相机参数
// Define Camera Render Object (for view / scene browsing)//s_cam:存储相机在 OpenGL 渲染空间中的投影矩阵和视图矩阵,用于 3D 显示//s_cam(窗口大小,窗口大小,焦距fx,fy,主点(光学中心在图像平面上的投影点),近平面,远平面)pangolin::OpenGlRenderState s_cam(pangolin::ProjectionMatrix(1024,768,mViewpointF,mViewpointF,512,389,0.1,1000),//设置相机观察位置和方向函数//(前三个是相机在世界坐标系的位置,相机注视的目标点,-Y方向为相机坐标的上方向)pangolin::ModelViewLookAt(mViewpointX,mViewpointY,mViewpointZ, 0,0,0,0.0,-1.0, 0.0));
4.5 创建可视化窗口
// Add named OpenGL viewport to window and provide 3D Handler//创建一个用于3D渲染的显示区域,并绑定一个3D交互控制器//创建绘图面板//.SetBounds(显示区域顶部相对窗口高度的比例,显示区域底部相对窗口高度的比例,//显示区域左边界的像素偏移,显示区域右边界相对窗口宽度的比例,纵横比、负号表示自动适应高度)//Handler3D(s_cam):绑定一个 3D 相机控制器,可以用鼠标旋转、缩放、平移视角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));
4.6 OpenGL矩阵与窗口初始化
//Twc:存储相机在世界坐标系下的位姿矩阵//SetIdentity():初始化为单位矩阵,相当于相机在原点、没有旋转、没有平移pangolin::OpenGlMatrix Twc;Twc.SetIdentity();//创建一个 OpenCV 窗口显示当前帧图像cv::namedWindow("ORB-SLAM2: Current Frame");
4.7 主循环
while(1){//清空上一帧的颜色缓存和深度缓存glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);mpMapDrawer->GetCurrentOpenGLCameraMatrix(Twc);//相机视角控制//如果视角跟随相机且确认跟随if(menuFollowCamera && bFollow){//让3D相机视角跟随Twc,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;}//使用 s_cam,虚拟摄像机状态 的相机视图矩阵渲染 d_cam,3D显示区域 这块区域d_cam.Activate(s_cam);//设置背景颜色为白色glClearColor(1.0f,1.0f,1.0f,1.0f);//绘制当前相机的坐标轴和相机模型mpMapDrawer->DrawCurrentCamera(Twc);//如果有关键帧和关键帧连线if(menuShowKeyFrames || menuShowGraph)mpMapDrawer->DrawKeyFrames(menuShowKeyFrames,menuShowGraph);if(menuShowPoints)mpMapDrawer->DrawMapPoints();//完成当前帧绘制并刷新窗口显示pangolin::FinishFrame();//绘制当前帧的2D图像cv::Mat im = mpFrameDrawer->DrawFrame();cv::imshow("ORB-SLAM2: Current Frame",im);//等待mT毫秒以控制刷新率cv::waitKey(mT);//当用户点击 Reset 时,恢复可视化界面和 SLAM 系统到初始状态if(menuReset){//重新打开显示关键帧、点云、共视图menuShowGraph = trmenuShowKeyFrames = true;menuShowPoints = true;//关闭定位模式menuLocalizationMode = false;if(bLocalizationMode)mpSystem->DeactivateLocalizationMode();bLocalizationMode = false;//重置相机跟随状态bFollow = true;menuFollowCamera = true;//调用系统重置mpSystem->Reset();menuReset = false;}if(Stop()){while(isStopped()){std::this_thread::sleep_for(std::chrono::microseconds(3000));}}if(CheckFinish())break;}
4.8 设置结束标志
SetFinish(); }