创作时间:2021年11月1日
当今科技发展速度飞快,无论是无人驾驶,还是虚拟现实,诸多领域都需要进行建图,并在此基础上进行开发处理。地图主要分为稀疏地图、稠密地图和语义地图,它们有着不同的优缺点以及应用,其中稠密地图占据着一个非常重要的位置,它能应用于导航、避障、交互等工作。
本文围绕着稠密点云建图这个话题展开,在Ubuntu-18.04的操作系统下利用TUM数据集进行RGBD稠密建图。文章首先简单地说明了稠密建图的原理,然后简述了RGBD相机,接着概述了TUM数据集,讲解了它的一些特点以及如何下载和使用数据集。接着,文章介绍了建图所需要用到的开源库,如OpenCV、Eigen等等,从简介、特点、安装、教程四个方面阐述,并给出学习这些库的网站。之后,文章讲述了本人自己写的一个基于C++的简单基于固定帧数选取法
和窗口压缩法
建图代码1的框架,且对部分代码进行了详细地分析,包括说明需要用到上述的哪些开源库,并呈现出建图的效果。最后,文章简单地总结了自己写的建图代码,并给出了未来探索的方向。
希望读者在阅读完本篇报告后能有一些收获,成为建图小将,同时,非常高兴读者能指出文章的不足之处,给予宝贵的建议。
RGB-D相机深度相机,又称深度相机,是2010年前后兴起的 一种相机,它可以通过红外结构光或ToF 原理测出物体与相机之间的距离(在建图中,物体与相机之间的距离非常重要)。
目前常用的 RGB-D 相机包括 Kinect/Kinect V2、Xtion Pro Live、RealSense等,在一些手机上人们也用它来识别人脸。
TUM数据集由慕尼黑工业大学的Computer Vision Lab公布。
TUM数据集的RGB图与深度图由RGBD相机2拍摄得到。
TUM数据集包含不同结构和纹理的数据、运动物体和3D物体重建。
TUM数据集的帧数大小不同,运动有快有慢,有手持的相机。
进入网页:
TUM官方数据集下载
下载所需的数据集:
sudo apt-get install build-essential libgtk2.0-dev libvtk7-dev libjpeg-dev libtiff5-dev libjasper-dev libopenexr-dev libtbb-dev
errorE: unable to locate libjasper-dev
sudo apt-get update
sudo apt-get install software-properties-common
sudo apt install libjasper1 libjasper-dev
进入OpenCV官网,选择OpenCV for Linux版本下载:
OpenCV下载
sudo make install
make -j4
sudo apt-get install libeigen3-dev
sudo apt-get install libeigen3-dev
Eigen官方介绍及教程
Eigen非官方速通教程
sudo apt-get install libpcl-dev pcl-tools
固定帧数选取法
。python associate.py rgb.txt depth.txt > associate.txt
python associate.py associate.txt groundtruth.txt > associate_with_groundtruth.txt
ifstream fin("~/associate_with_groundtruth.txt"); // 读取RGB图文件名、深度图文件名、相机位姿对齐的信息
for (int i = 0; i < 12; i++) fin >> data[i]; // 输入对齐的信息
vector colorImgs, depthImgs; // 彩色图和深度图
vector poses; // 相机位姿
colorImgs.push_back(cv::imread("RGB图名")); // 读取对齐的RGB图
depthImgs.push_back(cv::imread("深度图名")); // 读取对齐的深度图
poses.push_back(T); // 读取对齐的相机位姿
typedef pcl::PointXYZRGB PointT; //点类型(世界坐标)
typedef pcl::PointCloud PointCloud; //点云类型
PointCloud::Ptr pointCloud(new PointCloud); // 新建一个点云
PointCloud::Ptr slide_win(new PointCloud); // 新建一个点云压缩窗口
for (int i = 0; i < NImage; i+=IStep) {~} //均匀地选取关键
Eigen::Vector3d point; // 像素点的相机坐标
point[2] = double(d) / depthScale; // 计算相机坐标
point[0] = (u - cx) * point[2] / fx;
point[1] = (v - cy) * point[2] / fy;
Eigen::Vector3d pointWorld = T * point; // 将相机坐标转化为世界坐标
current->points.push_back(p); //将点塞进current点云中
pcl::StatisticalOutlierRemoval statistical_filter; // depth filter and statistical removal (深度滤波与统计去除)
statistical_filter.setInputCloud(current); // 将current点云进行深度滤波与统计去除
statistical_filter.filter(*tmp); // 将结果赋值给temp点云
(*slide_win) += *tmp; // 将滤波后的点云塞入压缩窗口slide_win中
pcl::VoxelGrid voxel_filter; // voxel filter(体素压缩)
voxel_filter.setInputCloud(slide_win); // 将slide_win点云进行体素滤波
voxel_filter.filter(*slide_win); // 将结果赋值给slide_win点云
(*pointCloud) += *slide_win; // 将滤波后点云塞入点云中
cv::imshow("img",colorImgs[i]); // 展示视频
pcl::visualization::CloudViewer viewer ("Viewer"); // 展示点云的窗口
viewer.showCloud(pointCloud); // 展示生成的点云
voxel_filter.setInputCloud(pointCloud); //对点云进行最后的全局压缩
voxel_filter.filter(*pointCloud); //将结果赋值给点云
pcl::io::savePCDFileBinary("map.pcd", *pointCloud); //保存点云文件
while (!viewer.wasStopped ()){} //使viewer窗口不自动退出
pcl_viewer map.pcd
#include
#include
using namespace std;
#include
#include
#include
#include
#include
#include
#include
#include
#include
#include
int NImage = 2486; //两次对齐后的图片数量
double NSlide = 1000000; //点云压缩窗口
int IStep = 360; //选取关键帧的步长
double resolution = 0.005; //点云分辨率
int main(int argc, char **argv) {
vector colorImgs, depthImgs; // 彩色图和深度图
vector poses; // 相机位姿
// 用fin读取associate_with_groundtruth.txt文件信息(RGB图文件名、深度图文件名、相机位姿对齐的信息)
ifstream fin("/home/lujunying/rgbd_dataset_freiburg3_long_office_household/associate_with_groundtruth.txt");
if (!fin) {
cerr << "cannot find pose file" << endl;
return 1;
}
//读取对齐的图片的信息(RGB图、深度图、相机位姿)
for (int i = 0; i < NImage; i++) { // 每张图片进行处理
string data[12];// 输入一张图的对齐信息
for (int i = 0; i < 12; i++) fin >> data[i];
colorImgs.push_back(cv::imread("/home/lujunying/rgbd_dataset_freiburg3_long_office_household/"+data[1])); // 读取对齐的RGB图(数据集的路径)
depthImgs.push_back(cv::imread("/home/lujunying/rgbd_dataset_freiburg3_long_office_household/"+data[3],-1)); // 读取对齐的深度图(数据集的路径)注意imread函数默认将图片转为RGB类型,故要进行类型转换
Eigen::Quaterniond q(atof(data[11].c_str()), atof(data[8].c_str()), atof(data[9].c_str()), atof(data[10].c_str())); // 读取对齐的相机旋转矩阵[四元数(w,x,y,z)]
Eigen::Isometry3d T(q);
T.pretranslate(Eigen::Vector3d(atof(data[5].c_str()), atof(data[6].c_str()), atof(data[7].c_str()))); // 读取对齐的相机的平移向量
poses.push_back(T); // 对齐的相机的位姿
}
// 计算点云并拼接
// 相机内参(见TUM数据集相机内参)
double cx = 320.1;
double cy = 247.6;
double fx = 535.4;
double fy = 539.2;
double depthScale = 5000.0;
cout << "正在将图像转换为点云..." << endl;
// 定义点云使用的格式:这里用的是XYZRGB
typedef pcl::PointXYZRGB PointT; //点类型(世界坐标)
typedef pcl::PointCloud PointCloud; //点云类型
// 新建一个点云
PointCloud::Ptr pointCloud(new PointCloud);
// 新建一个点云压缩窗口
PointCloud::Ptr slide_win(new PointCloud);
// 选择并处理关键帧,生成并展示两次滤波后的点云
pcl::visualization::CloudViewer viewer ("Viewer"); // 开启展示点云的窗口
for (int i = 0; i < NImage; i+=IStep) { // 均匀选择图片作为关键帧,并处理
PointCloud::Ptr current(new PointCloud);
cout << "转换关键帧中: " << i + 1 << endl;
cv::Mat color = colorImgs[i];
cv::Mat depth = depthImgs[i];
Eigen::Isometry3d T = poses[i];
for (int v = 0; v < color.rows; v++) // 处理图片上的像素点
for (int u = 0; u < color.cols; u++) {
unsigned int d = depth.ptr(v)[u]; //获取深度值
if (d == 0) continue; // 若没有测量到该像素的深度,则跳转到下一个像素
Eigen::Vector3d point; // 像素的相机坐标
point[2] = double(d) / depthScale; // d除以scale变为米的单位
point[0] = (u - cx) * point[2] / fx;
point[1] = (v - cy) * point[2] / fy;
Eigen::Vector3d pointWorld = T * point; // 将相机坐标变为世界坐标
PointT p; // 点(XYZRGB格式)
p.x = pointWorld[0];
p.y = pointWorld[1];
p.z = pointWorld[2];
p.b = color.data[v * color.step + u * color.channels()];
p.g = color.data[v * color.step + u * color.channels() + 1];
p.r = color.data[v * color.step + u * color.channels() + 2];
current->points.push_back(p); //将点塞进current点云中
}
// depth filter and statistical removal (深度滤波与统计去除)
cout << "current点云共有" << current->size() << "个点." << endl;
PointCloud::Ptr tmp(new PointCloud);
pcl::StatisticalOutlierRemoval statistical_filter;
statistical_filter.setMeanK(50);
statistical_filter.setStddevMulThresh(1.0);
statistical_filter.setInputCloud(current); // 将current点云进行深度滤波与统计去除
statistical_filter.filter(*tmp); // 将结果赋值给temp点云
current.reset(); // 释放current点云内存
cout << "tmp点云共有" << tmp->size() << "个点." << endl;
(*slide_win) += *tmp; // 将滤波后的点云塞入压缩窗口slide_win中
tmp.reset(); // 释放temp点云内存
cout << "slide_win点云共有" << slide_win->size() << "个点." << endl;
if(slide_win->size() > NSlide || slide_win->size() == NSlide || i == 0 || (i+IStep)>( NImage-1)){ //如果slide_win满足体素压缩的条件
// voxel filter(体素压缩)
pcl::VoxelGrid voxel_filter;
voxel_filter.setLeafSize(resolution, resolution, resolution);
voxel_filter.setInputCloud(slide_win); // 将slide_win点云进行体素滤波
voxel_filter.filter(*slide_win); // 将结果赋值给slide_win点云
cout << "压缩后slide_win点云共有" << slide_win->size() << "个点." << endl;
(*pointCloud) += *slide_win; // 将滤波后的slide_win点云塞入点云中
slide_win.reset(new PointCloud); // 释放slide_win点云内存
}
cout << "pointCloud点云共有" << pointCloud->size() << "个点." << endl;
cout << "-------------------------------------------------------------------------------" << endl;
// 展示视频与生成的点云
cv::imshow("img",colorImgs[i]); // 展示视频
cv::waitKey(30);
viewer.showCloud(pointCloud); // 展示点云
}
// 对点云进行最后的全局压缩
cout << "两次滤波后点云共有" << pointCloud->size() << "个点." << endl;
pointCloud->is_dense = false; // 这个没什么用
pcl::VoxelGrid voxel_filter; // 最后的全局压缩
voxel_filter.setLeafSize(resolution, resolution, resolution);
voxel_filter.setInputCloud(pointCloud);
voxel_filter.filter(*pointCloud);
viewer.showCloud(pointCloud);
//保存生成的点云文件
cout << "最终两次滤波后点云共有" << pointCloud->size() << "个点." << endl;
pcl::io::savePCDFileBinary("map.pcd", *pointCloud);
//结束程序
while (!viewer.wasStopped ()){} //保持viewer窗口,不自动退出
return 0;
}
窗口压缩
的方法建立点云,极大地减少了点云不必要的内存,加大了建图的规模。固定帧数选取法
,优点是通俗易懂、编程简单,缺点是具有较高的随机性,关键帧的质量一般,比如运动很慢的时候,就会选择大量相似的关键帧,冗余,运动快的时候又丢失了很多重要的帧关键帧。未来将学习ORB-SLAM2[5]以及GCNv2[6]的关键帧提取和稠密重建的相关算法,并在此基础上进行改进。[1] 高翔,张涛.《视觉SLAM十四讲:从理论到实践》.(第2版).北京:电子工业出版社,2019.
[2] Stephen Prata.《C++ Primer Plus》.(第6版中文版).北京:人民邮电出版社,2020.7.
[3] T. Barfbot, State estimation fbr robotics: A matrix lie group approach, 2016.
[4] R. Mur-Artal, J. M. M. Montiel, and J. D. Tards, “ORB-SLAM: A versatile and accurate monocular slam system,” IEEE Trans. Robot., vol. 31, no. 5, pp. 1147–1163, Oct. 2015.
[5] R. Mur-Artal and J. D. Tardós, “ORB-SLAM2: An open-source SLAM system for monocular, stereo and RGB-D cameras,” IEEE Trans. Robot., vol. 33, no. 5, pp. 1255–1262, Oct. 2017.
[6] J. Tang, J. Folkesson, and P. Jensfelt, “GCNv2: Efficient Correspondence Prediction
for Real-Time SLAM,” IEEE ROBOTICS AND AUTOMATION LETTERS, VOL. 4, NO. 4, OCTOBER 2019.
代码见建图实战的第4点。 ↩︎
点我了解RGBD相机 ↩︎ ↩︎
点我了解TUM数据集 ↩︎
点我了解OpenCV ↩︎
点我了解Eigen ↩︎
点我了解PCL ↩︎
点我了解associate.py ↩︎