SLAM可视化绘图库——Pangolin教程(二)

SLAM可视化绘图库——Pangolin教程(二)

  • Task3:为Pangolin添加控件
    • 代码解析
  • Task 4:多视图与图片显示
    • 代码解析
  • 总结

在上一讲中,我们学习了如何使用Pangolin绘制一个简单的动画并在多线程中运行,今天我们将继续学习如果对Pangolin的视窗进行分割并添加简单的控件。

  • 教程代码:https://github.com/yuntianli91/pangolin_tutorial
  • ROS Pangolin手册:pangolin namespace

Task3:为Pangolin添加控件

我们在上一讲程序的基础上,为视窗添加一个控制面板,展示一些简单的控件操作,代码如下:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
#include <pangolin/pangolin.h>
#include <string>
#include <iostream>
// ----------------------------------------------------------------- //

void SampleMethod()
{
    std::cout << "You typed ctrl-r or pushed reset" << std::endl;
    // std::cout << "Window width: " << i << std::endl;
}
// ----------------------------------------------------------------------- //
int main(/*int argc, char* argv[]*/)
{  

    // 创建视窗
    pangolin::CreateWindowAndBind("Main",640,480);
    // 启动深度测试
    glEnable(GL_DEPTH_TEST);
    // 创建一个摄像机
    pangolin::OpenGlRenderState s_cam(
        pangolin::ProjectionMatrix(640,480,420,420,320,240,0.1,1000),
        pangolin::ModelViewLookAt(-0,0.5,-3, 0,0,0, pangolin::AxisY)
    );
    // 分割视窗
    const int UI_WIDTH = 180;

    // 右侧用于显示视口
    pangolin::View& d_cam = pangolin::CreateDisplay()
        .SetBounds(0.0, 1.0, pangolin::Attach::Pix(UI_WIDTH), 1.0, -640.0f/480.0f)
        .SetHandler(new pangolin::Handler3D(s_cam));
    // 左侧用于创建控制面板
    pangolin::CreatePanel("ui")
        .SetBounds(0.0, 1.0, 0.0, pangolin::Attach::Pix(UI_WIDTH));

    // 创建控制面板的控件对象,pangolin中
    pangolin::Var<bool> A_Button("ui.a_button", false, false);  // 按钮
    pangolin::Var<bool> A_Checkbox("ui.a_checkbox", false, true); // 选框
    pangolin::Var<double> Double_Slider("ui.a_slider", 3, 0, 5); //double滑条
    pangolin::Var<int> Int_Slider("ui.b_slider", 2, 0, 5); //int滑条
    pangolin::Var<std::string> A_string("ui.a_string", "Hello Pangolin");

    pangolin::Var<bool> SAVE_IMG("ui.save_img", false, false);  // 按钮
    pangolin::Var<bool> SAVE_WIN("ui.save_win", false, false); // 按钮
    pangolin::Var<bool> RECORD_WIN("ui.record_win", false, false); // 按钮

    pangolin::Var<std::function<void()>> reset("ui.Reset", SampleMethod);//

    // 绑定键盘快捷键
    // Demonstration of how we can register a keyboard hook to alter a Var
    pangolin::RegisterKeyPressCallback(pangolin::PANGO_CTRL + 'b', pangolin::SetVarFunctor<double>("ui.a_slider", 3.5));

    // Demonstration of how we can register a keyboard hook to trigger a method
    pangolin::RegisterKeyPressCallback(pangolin::PANGO_CTRL + 'r', SampleMethod);
    // Default hooks for exiting (Esc) and fullscreen (tab).
    while( !pangolin::ShouldQuit() )
    {
        // Clear entire screen
        glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);    

        // 各控件的回调函数
        if(pangolin::Pushed(A_Button))
            std::cout << "Push button A." << std::endl;
       
        if(A_Checkbox)
            Int_Slider = Double_Slider;
        // 保存整个win
        if( pangolin::Pushed(SAVE_WIN) )
        pangolin::SaveWindowOnRender("window");
        // 保存view
        if( pangolin::Pushed(SAVE_IMG) )
        d_cam.SaveOnRender("cube");
        // 录像
        if( pangolin::Pushed(RECORD_WIN) )
        pangolin::DisplayBase().RecordOnRender("ffmpeg:[fps=50,bps=8388608,unique_filename]//screencap.avi");
        d_cam.Activate(s_cam);
        // glColor3f(1.0,0.0,1.0);
        pangolin::glDrawColouredCube();

        // Swap frames and Process Events
        pangolin::FinishFrame();
    }

    return 0;
}

程序运行结果如下:
在这里插入图片描述

代码解析

1
2
3
4
5
6
7
8
9
 // 分割视窗
 const int UI_WIDTH = 180;
 // 右侧用于显示视口
 pangolin::View& d_cam = pangolin::CreateDisplay()
     .SetBounds(0.0, 1.0, pangolin::Attach::Pix(UI_WIDTH), 1.0, -640.0f/480.0f)
     .SetHandler(new pangolin::Handler3D(s_cam));
 // 左侧用于创建控制面板
 pangolin::CreatePanel("ui")
     .SetBounds(0.0, 1.0, 0.0, pangolin::Attach::Pix(UI_WIDTH));

与前两例相同,我们首先依旧需要创建一个视窗和对应的摄像机模型,随后我们在将视窗的坐标180像素宽度位置使用CreatePanel()命令创建一个面板,并给这个面板明明为“ui”,这里"ui"是面板的tag名称,后续所有控制的操作都通过这个tag绑定到对应的面板上。视窗的其余部分则为用于显示的viewport,创建方式和上一节相同。

1
2
3
4
5
6
7
8
9
10
11
12
  // 创建控制面板的控件对象,pangolin中
    pangolin::Var<bool> A_Button("ui.a_button", false, false);  // 按钮
    pangolin::Var<bool> A_Checkbox("ui.a_checkbox", false, true); // 选框
    pangolin::Var<double> Double_Slider("ui.a_slider", 3, 0, 5); //double滑条
    pangolin::Var<int> Int_Slider("ui.b_slider", 2, 0, 5); //int滑条
    pangolin::Var<std::string> A_string("ui.a_string", "Hello Pangolin");

    pangolin::Var<bool> SAVE_IMG("ui.save_img", false, false);  // 按钮
    pangolin::Var<bool> SAVE_WIN("ui.save_win", false, false); // 按钮
    pangolin::Var<bool> RECORD_WIN("ui.record_win", false, false); // 按钮

    pangolin::Var<std::function<void()>> reset("ui.Reset", SampleMethod);//

随后,我们来创建一系列常用控件,Pangolin将所有“控件”视为一个pangolin::Var对象,该对象是一个模板类,我们可以向其中传递自定义的类型模板,亦可使用Pangolin预先定义的类模板。这里将常用的pangolin::Var对象整理如下:

  • pangolin::VarboolVar对象,创建参数依次为控件的tag、初始值以及是否可以toggle。当toggle设置为true时,该对象表示一个选框(Checkbox);设置为false时则表示一个按钮(Button)。初始值对于设置为truefalse会影响选框是否被选中,对于按钮来说则没有影响,不过出于习惯,一般都会设置为false。控件的tag是唯一的,命名格式为panel_tag.controller_tag,例如这里我们所有控件需要板顶的面板tag为“ui”,因此所有的控件tag都命名为ui.xxx的形式,以下所有的控件tag都遵从这一规范,不再赘述。
  • pangolin::Var:这一类Var对象为常见的滑条对象,创建参数依次为控件tag、初始值、最小值、最大值和logscale。其中logscale表示是否以对数坐标形式显示;最小值和最大值控制滑条的范围,如果不设置的话默认最小值为0,最大值为1;主要注意的是,这里的初始值值得是滑条上初始显示的数字,因此其不需要在滑条的范围内,只不过在用户移动滑条后,显示的数字会更新为滑条当前位置对应的数字。
  • pangolin::Var>:这一类控件同样实现按钮控件的功能,只是其在创建时传入一个std::function函数对象,因此不需要在后续循环中进行回调函数的书写。不过如果回调函数中如果需要进行参数的传入和传出,使用std::function会比较麻烦,因此其常用来编写一些void(void)类型的简单功能函数。

需要注意的是,上述所有控件的必要参数只有控件tag和初始值,其他参数不存在时pangolin会自动调用默认参数进行处理。此外,代码中还掩饰了绑定快捷键的相关操作,这里就不细说了。

1
2
3
4
5
6
7
8
9
10
11
12
13
14
  if(pangolin::Pushed(A_Button))
            std::cout << "Push button A." << std::endl;
       
        if(A_Checkbox)
            Int_Slider = Double_Slider;
       
        if( pangolin::Pushed(SAVE_WIN) )
        pangolin::SaveWindowOnRender("window");

        if( pangolin::Pushed(SAVE_IMG) )
        d_cam.SaveOnRender("cube");

        if( pangolin::Pushed(RECORD_WIN) )
        pangolin::DisplayBase().RecordOnRender("ffmpeg:[fps=50,bps=8388608,unique_filename]//screencap.avi");

最后,在while循环中,我们为Checkbox和Button编写了对应的回调函数,对于Checkbox来说,直接判断其本身状态为truefalse即可;而Button对象则需要使用pangolin::Pushed(string tag)函数判断其是否按下。

Task 4:多视图与图片显示

注意:这里的多视图只是功能上用于在视窗的不同区域叠加显示不同功能模块的多视图,而非真正意义上将视窗严格划分的多视图,pangolin中提供了SimpleMultiDisplay例子用于演示整整的多视图分割,但据作者说只是demo,运行效果并不稳定,有兴趣的同学可以进一步研究。

在SLAM的可视化中,有时我们期望实时显示相机的图像和特征点跟踪情况(例如VINS-Mono),pangolin同样提供了用于显示图像的一系列功能,下面的代码分别在视窗左上角和右下角实时显示了EuRoc数据集中的图像:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
#include <opencv2/opencv.hpp>
#include <pangolin/pangolin.h>

int main(int argc, char** argv){
    // 创建视窗
    pangolin::CreateWindowAndBind("MultiImage", 752, 480);
    // 启动深度测试
    glEnable(GL_DEPTH_TEST);
    // 设置摄像机
    pangolin::OpenGlRenderState s_cam(
        pangolin::ProjectionMatrix(752, 480, 420, 420, 320, 320, 0.1, 1000),
        pangolin::ModelViewLookAt(-2, 0, -2, 0, 0, 0, pangolin::AxisY)
    );
    // ---------- 创建三个视图 ---------- //
    pangolin::View& d_cam = pangolin::Display("cam")
        .SetBounds(0., 1., 0., 1., -752/480.)
        .SetHandler(new pangolin::Handler3D(s_cam));
   
    pangolin::View& cv_img_1 = pangolin::Display("image_1")
        .SetBounds(2/3.0f, 1.0f, 0., 1/3.0f, 752/480.)
        .SetLock(pangolin::LockLeft, pangolin::LockTop);
   
    pangolin::View& cv_img_2 = pangolin::Display("image_2")
        .SetBounds(0., 1/3.0f, 2/3.0f, 1.0, 752/480.)
        .SetLock(pangolin::LockRight, pangolin::LockBottom);
    // 创建glTexture容器用于读取图像
    pangolin::GlTexture imgTexture1(752, 480, GL_RGB, false, 0, GL_BGR, GL_UNSIGNED_BYTE);
    pangolin::GlTexture imgTexture2(752, 480, GL_RGB, false, 0, GL_BGR, GL_UNSIGNED_BYTE);

    while(!pangolin::ShouldQuit()){
        // 清空颜色和深度缓存
        glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
        // 启动相机
        d_cam.Activate(s_cam);
        // 添加一个立方体
        glColor3f(1.0f, 1.0f, 1.0f);
        pangolin::glDrawColouredCube();
        // 从文件读取图像
        cv::Mat img1 = cv::imread("../task4/img/img1.png");
        cv::Mat img2 = cv::imread("../task4/img/img2.png");
        // 向GPU装载图像
        imgTexture1.Upload(img1.data, GL_BGR, GL_UNSIGNED_BYTE);
        imgTexture2.Upload(img2.data, GL_BGR, GL_UNSIGNED_BYTE);
        // 显示图像
        cv_img_1.Activate();
        glColor3f(1.0f, 1.0f, 1.0f); // 设置默认背景色,对于显示图片来说,不设置也没关系
        imgTexture1.RenderToViewportFlipY(); // 需要反转Y轴,否则输出是倒着的
       
        cv_img_2.Activate();
        glColor3f(1.0f, 1.0f, 1.0f); // 设置默认背景色,对于显示图片来说,不设置也没关系
        imgTexture2.RenderToViewportFlipY();

        pangolin::FinishFrame();
    }

    return 0;
}

程序运行结果如下:
在这里插入图片描述

代码解析

1
2
3
4
5
6
7
8
9
10
11
 pangolin::View& d_cam = pangolin::Display("cam")
        .SetBounds(0., 1., 0., 1., -752/480.)
        .SetHandler(new pangolin::Handler3D(s_cam));
   
    pangolin::View& cv_img_1 = pangolin::Display("image_1")
        .SetBounds(2/3.0f, 1.0f, 0., 1/3.0f, 752/480.)
        .SetLock(pangolin::LockLeft, pangolin::LockTop);
   
    pangolin::View& cv_img_2 = pangolin::Display("image_2")
        .SetBounds(0., 1/3.0f, 2/3.0f, 1.0, 752/480.)
        .SetLock(pangolin::LockRight, pangolin::LockBottom);

在这个例子中,我们首先创建在视窗中创建了三个视图,其中一个是我们很熟悉的相机视图,在本例中我们特意让相机视图充满了整个视窗,以演示我们前面说明的这里的多视图其实是通过视图“叠加”实现的。紧接着我们创建了另外两个视图用于显示图片,其中一个视图位于左上角,一个视图位于右下角。

这里我们着重解释下创建视图函数中的第五个参数。我们注意到,在后两个视图的创建中,该参数是正值,而在创建动画视窗视使用的是负值。该参数实际上表征的是视图的分辨率,当该参数取正值时,pangolin会将由前四个参数设置的视图大小进行裁剪,以满足所设置的分辨率;当该值为负值时,pangolin会在将图片拉伸以充满由前四个参数设置的视图范围。

此外,由于后两个视图并不是交互视图,因此我们没有使用setHandler()设置视图句柄,而是使用了setLock()函数设置了视图锁定的位置,该函数会在我们缩放整个视窗后,按照设定的lock选项自动锁定对其位置。例如在本例中,我们将左上角的视图设置为left和top锁定,右下角的视图则设置为right和bottom锁定。

1
2
3
 // 创建glTexture容器用于读取图像
    pangolin::GlTexture imgTexture1(752, 480, GL_RGB, false, 0, GL_BGR, GL_UNSIGNED_BYTE);
    pangolin::GlTexture imgTexture2(752, 480, GL_RGB, false, 0, GL_BGR, GL_UNSIGNED_BYTE);

随后我们需要创建两个图像纹理容器pangolin::GlTexture用于向上面创建的视图装载图像,该对象的入口参数依次为图像宽度、图像高度、pangolin的内部图像存储格式,是否开启现行采样,边界大小(像素)、gl图像存储格式以及gl数据存储格式。由于我们使用OpenCV从文件中读取并存储图像,cv::Mat的图像存储顺序为BGR,而数据存储格式为uint型,因此最后两个参数我们分别设置为GL_BGRGL_UNSIGNED_BYTE,至于pangolin的内部存储格式,对图片的显示影响不大,因此一般都设置为GL_RGB

需要注意的是,这里图像的宽度和高度一定要设置为和原图片一致,否则会导致图像无法正常显示。另外两个参数默认设置为false0即可。

1
2
3
4
5
6
7
8
9
10
11
 // 向GPU装载图像
 imgTexture1.Upload(img1.data, GL_BGR, GL_UNSIGNED_BYTE);
 imgTexture2.Upload(img2.data, GL_BGR, GL_UNSIGNED_BYTE);
 // 显示图像
 cv_img_1.Activate();
 glColor3f(1.0f, 1.0f, 1.0f); // 设置默认背景色,对于显示图片来说,不设置也没关系
 imgTexture1.RenderToViewportFlipY(); // 需要反转Y轴,否则输出是倒着的
       
 cv_img_2.Activate();
 glColor3f(1.0f, 1.0f, 1.0f); // 设置默认背景色,对于显示图片来说,不设置也没关系
 imgTexture2.RenderToViewportFlipY();

最后,我们通过创建的pangolin::GlTexture对象向GPU中装载图像,由于该对象只接受uchar*对象,因此需要传递cv::Matdata成员,而不能传递cv::Mat本身;另外两个参数则和我们在创建pangolin::GlTexture对象时使用的最后两个参数一致。

在装载完图像后,我们依次激活视窗、设置默认背景色、最后渲染显示图像,这里原始渲染出的图像是倒着的,因此我们翻转了Y轴,具体原因暂不明。

总结

至此,我们的pangolin程序已经初步有了SLAM可视化的雏形,在下一讲中,我们将继续学习如何使用pangolin绘制函数曲线和绘制带有位姿变换的相机模型。