我们现在已经有了单目相机采集到的原始图像,对应的深度图,以及对应的相机位姿(以往博客有提及),接下来我们就可以用这些数据进行拼接点云生成三维稠密点云地图了。
首先还是先看例程,基于SLAM14讲5.4的源码:本机环境Eigen3,pcl1.7 opencv3.3.1
源码提供了5张彩色图和深度图以及对应的相机位姿(平移向量xyz旋转四元数qxqyqzqw),
例程效果如下:
我们可以根据例程 在对应的数据集里面放自己彩色图 深度图 和对应的相机位姿,生成自己的点云地图,比如上篇博客刚刚生成的深度图,该数据集对应的点云图如下所示,(数据姿态有问题,造成地图分层以及对应错位):
主程序joinMap.cpp
#include
#include
using namespace std;
#include
#include
#include
#include // for formating strings
#include
#include
#include
int main( int argc, char** argv )
{
vector colorImgs, depthImgs; // 彩色图和深度图
vector> poses; // 相机位姿
ifstream fin("./pose.txt");
if (!fin)
{
cerr<<"请在有pose.txt的目录下运行此程序"<>d;
Eigen::Quaterniond q( data[6], data[3], data[4], data[5] );
Eigen::Isometry3d T(q);
T.pretranslate( Eigen::Vector3d( data[0], data[1], data[2] ));
poses.push_back( T );
}
// 计算点云并拼接
// 相机内参
double cx = 325.5;
double cy = 253.5;
double fx = 518.0;
double fy = 519.0;
double depthScale = 1000.0;
cout<<"正在将图像转换为点云..."< PointCloud;
// 新建一个点云
PointCloud::Ptr pointCloud( new PointCloud );
for ( int i=0; i<5; i++ )
{
cout<<"转换图像中: "< ( v )[u]; // 深度值
if ( d==0 ) continue; // 为0表示没有测量到
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;
PointT p ;
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 ];
pointCloud->points.push_back( p );
}
}
pointCloud->is_dense = false;
cout<<"点云共有"<size()<<"个点."<
CMakeLists.txt如下:
cmake_minimum_required( VERSION 2.8 )
project( joinMap )
set( CMAKE_BUILD_TYPE Release )
set( CMAKE_CXX_FLAGS "-std=c++11 -O3" )
# opencv
find_package( OpenCV REQUIRED )
include_directories( ${OpenCV_INCLUDE_DIRS} )
# eigen
include_directories( "/usr/include/eigen3/" )
# pcl
find_package( PCL REQUIRED COMPONENT common io )
include_directories( ${PCL_INCLUDE_DIRS} )
add_definitions( ${PCL_DEFINITIONS} )
add_executable( joinMap joinMap.cpp )
target_link_libraries( joinMap ${OpenCV_LIBS} ${PCL_LIBRARIES} )