ORB-SLAM2和iai_kinect2中的双重标定问题

根据高翔博士博客1做使用Kinect2跑ORB-SLAM2的过程中,发现了一个关于双重标定的问题。

Kinect2使用iai_kinect22作为驱动接口。kinect2_bridge提供了以下的Quater HDTopics:

1
2
3
4
5
6
7
8
9
10
11
12
/kinect2/qhd/camera_info
/kinect2/qhd/image_color
/kinect2/qhd/image_color/compressed
/kinect2/qhd/image_color_rect
/kinect2/qhd/image_color_rect/compressed
/kinect2/qhd/image_depth_rect
/kinect2/qhd/image_depth_rect/compressed
/kinect2/qhd/image_mono
/kinect2/qhd/image_mono/compressed
/kinect2/qhd/image_mono_rect
/kinect2/qhd/image_mono_rect/compressed
/kinect2/qhd/points

而博客3上提供的代码中,订阅的是/kinect2/sd/image_color_rect/kinect2/sd/image_depth_rect两个Topics。因为我使用的是QHD画质,所以我依葫芦画瓢,将订阅的Topics修改为/kinect2/qhd/image_color_rect/kinect2/qhd/image_depth_rect

而在运行kinect2_bridge节点之前,需要在kinect2_bridge/data/<serialnumber>文件夹下放入Kinect的校正值文件。同时,在建立ORB_SLAM2的实例的时候,也需要提供一个校正参数的yaml文件strSettingsFile:

1
System::System(const string &strVocFile, const string &strSettingsFile, const eSensor sensor,const bool bUseViewer)

那么,会不会发生图片进行了两次校正的情况呢?

根据源代码kinect2_bridge.cpp中显示,在processColor的函数中:

1
2
3
4
if(status[COLOR_QHD_RECT] || status[MONO_QHD_RECT])
{
cv::remap(images[COLOR_HD], images[COLOR_QHD_RECT], map1LowRes, map2LowRes, cv::INTER_AREA);
}

image_color_rect这个Topic中,图片是会使用OpenCV的remap函数对进行还原,就是说,image_color_rect这个Topic的图片,是已经经过校正操作了。

而在ORB_SLAM2的源代码Frame.cc文件中,我们可以找到UndistortKeyPoints这个函数,它的作用是对每一帧图像中的关键点使用OpenCV提供的undistortPoints函数,根据校正文件提供的阐述进行修正。

就是说,我在一个已经经过修正的图像中找出关键点,并且再对关键点根据校正值再进行了一次修正,而这是不对的。

所以,应该将订阅的image_color_rect这个Topic修改为image_color,读取的是一个未经校正的图片,然后仅在ORB_SLAM2中对图片进行校正操作。


  1. http://www.cnblogs.com/gaoxiang12/p/5161223.html↩︎

  2. https://github.com/code-iai/iai_kinect2↩︎

  3. http://www.cnblogs.com/gaoxiang12/p/5161223.html↩︎