2020-4-28更新

commit:之前的深度图无法动态显示,参考​​这篇博客​​,copy过来动态显示的版本,下面为代码

代码

#include <pcl/range_image/range_image.h>
#include <pcl/visualization/range_image_visualizer.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <pcl/console/parse.h>
#include <pcl/io/io.h>
#include <pcl/io/pcd_io.h>

void
setViewerPose(pcl::visualization::PCLVisualizer& viewer, const Eigen::Affine3f& viewer_pose)
{
Eigen::Vector3f pos_vector = viewer_pose * Eigen::Vector3f(0, 0, 0);
Eigen::Vector3f look_at_vector = viewer_pose.rotation() * Eigen::Vector3f(0, 0, 1) + pos_vector;
Eigen::Vector3f up_vector = viewer_pose.rotation() * Eigen::Vector3f(0, -1, 0);
viewer.setCameraPosition(
pos_vector[0],
pos_vector[1],
pos_vector[2],
look_at_vector[0],
look_at_vector[1],
look_at_vector[2],
up_vector[0],
up_vector[1],
up_vector[2]);
}

int
main (int argc, char** argv) {

pcl::PointCloud<pcl::PointXYZ> pointCloud;
/*
//生成数据
for (float y=-0.5f; y<=0.5f; y+=0.01f)
{
for (float z=-0.5f; z<=0.5f; z+=0.01f)
{
pcl::PointXYZ point;
point.x = 2.0f - y;
point.y = y;
point.z = z;
pointCloud.points.push_back(point);
}
}
pointCloud.width = (uint32_t) pointCloud.points.size();
pointCloud.height = 1;
*/

//读取数据
std::string Filename="./Building1.pcd";
pcl::io::loadPCDFile(Filename,pointCloud);
/*以1度为角分辨率,从上面创建的点云创建深度图像。*/
float angularResolution = (float) ( 1.0f * (M_PI/180.0f)); // 1度转弧度
/*模拟深度传感器在水平方向的最大采样角度:360°视角。*/
float maxAngleWidth = (float) (360.0f * (M_PI/180.0f)); // 360.0度转弧度
/*模拟深度传感器在垂直方向的最大采样角度:180°视角。*/
float maxAngleHeight = (float) (180.0f * (M_PI/180.0f)); // 180.0度转弧度
/*
sensorPose定义模拟深度传感器的6自由度位置:
横滚角roll、俯仰角pitch、偏航角yaw,默认初始值均为0。
*/
Eigen::Affine3f sensorPose = (Eigen::Affine3f)Eigen::Translation3f(0.0f, 0.0f, 0.0f);
/*
定义坐标轴正方向:
CAMERA_FRAME:X轴向右,Y轴向下,Z轴向前;
LASER_FRAME:X轴向前,Y轴向左,Z轴向上;
*/
pcl::RangeImage::CoordinateFrame coordinate_frame = pcl::RangeImage::CAMERA_FRAME;
/*
noiseLevel设置周围点对当前点深度值的影响:
如 noiseLevel=0.05,可以理解为,深度距离值是通过查询点半径为 Scm 的圆内包含的点用来平均计算而得到的。
*/
float noiseLevel=0.00;
/*
min_range设置最小的获取距离,小于最小获取距离的位置为盲区
*/
float minRange = 0.0f;
/*border_size获得深度图像的边缘的宽度:在裁剪图像时,如果 borderSize>O ,将在图像周围留下当前视点不可见点的边界*/
int borderSize = 1;

boost::shared_ptr<pcl::RangeImage> range_image_ptr(new pcl::RangeImage);
pcl::RangeImage& range_image = *range_image_ptr;
range_image.createFromPointCloud(pointCloud, angularResolution, maxAngleWidth, maxAngleHeight, sensorPose, coordinate_frame, noiseLevel, minRange, borderSize);
std::cout << range_image << "\n"; //重载了<<运算符

//创建3D视图并且添加点云进行显示
pcl::visualization::PCLVisualizer viewer("3D Viewer");
viewer.setBackgroundColor(1, 1, 1);
pcl::visualization::PointCloudColorHandlerCustom<pcl::PointWithRange> range_image_color_handler(range_image_ptr, 0, 0, 0);
viewer.addPointCloud(range_image_ptr, range_image_color_handler, "range image");
viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 3, "range image");

viewer.initCameraParameters();
setViewerPose(viewer, range_image.getTransformationToWorldSystem());

//显示深度图像
pcl::visualization::RangeImageVisualizer range_image_widget("Range image");
//range_image_widget.setRangeImage(range_image);
range_image_widget.showRangeImage(range_image); //图像可视化方式显示深度图像
Eigen::Affine3f scene_sensor_pose(Eigen::Affine3f::Identity());
//主循环
while (!viewer.wasStopped())
{
range_image_widget.spinOnce();
viewer.spinOnce();
pcl_sleep(0.01);
if (1)
{
scene_sensor_pose = viewer.getViewerPose();
range_image.createFromPointCloud(pointCloud,
angularResolution, pcl::deg2rad(360.0f),
pcl::deg2rad(180.0f),
scene_sensor_pose,
pcl::RangeImage::LASER_FRAME,
noiseLevel,
minRange,
borderSize);
range_image_widget.showRangeImage(range_image);
}
}

}

原文

背景:

有时候我们获取的点云数据是从一个视点获取的,为了使用深度图相关的计算方法,以提高效率,我们需要将点云数据转换为深度图。这两种数据的主要区别在于,点云数据需要通过k-d tree等索引来对数据进行检索,而深度图像和图像类似,可以通过上下左右等近邻来直接进行索引。本例程就是将点云数据转换为深度图像,进而使用PCL内部只适用于深度图的算法来进行曲面重建等。

代码(详细注释):

#include <pcl/range_image/range_image.h>
#include <pcl/range_image/range_image_planar.h>
#include <pcl/io/io.h>
#include <pcl/io/pcd_io.h>
#include <pcl/features/integral_image_normal.h>
#include <pcl/visualization/cloud_viewer.h>
#include <pcl/point_types.h>
#include <pcl/features/normal_3d.h>
#include <pcl/console/print.h>
#include <pcl/surface/organized_fast_mesh.h>
#include <pcl/console/time.h>
#include <Eigen/StdVector>
#include <Eigen/Geometry>
#include <iostream>
#include <pcl/surface/impl/organized_fast_mesh.hpp>
#include <boost/thread/thread.hpp>

#include <pcl/common/common_headers.h>

#include <pcl/visualization/range_image_visualizer.h>
#include <pcl/visualization/pcl_visualizer.h>
#include <pcl/console/parse.h>


#include <pcl/visualization/common/float_image_utils.h>//保存深度图像
#include <pcl/io/png_io.h>//保存深度图像
using namespace pcl::console;
int main (int argc, char** argv) {


// Generate the data
if (argc<2)
{

print_error ("Syntax is: %s input.pcd -w 640 -h 480 -cx 320 -cy 240 -fx 525 -fy 525 -type 0 -size 2\n", argv[0]);
print_info (" where options are:\n");
print_info (" -w X = width of detph iamge ");

return -1;
}
std::string filename = argv[1];//将命令行的第二个参数传给filename

//默认的参数
int width=640,height=480,size=2,type=0;
float fx=525,fy=525,cx=320,cy=240;

//命令行解析
//可以在命令行输入附加参数
parse_argument (argc, argv, "-w", width);//深度图像宽度
parse_argument (argc, argv, "-h", height);//深度图像高度
parse_argument (argc, argv, "-cx", cx);//光轴在深度图像上的x坐标
parse_argument (argc, argv, "-cy", cy);//光轴在深度图像上的y坐标
parse_argument (argc, argv, "-fx", fx);//水平方向焦距
parse_argument (argc, argv, "-fy", fy);//垂直方向焦距
parse_argument (argc, argv, "-type", type);//曲面重建时三角化的方式
parse_argument (argc, argv, "-size", size);//曲面重建时的面片的大小
//convert unorignized point cloud to orginized point cloud begin
pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in(new pcl::PointCloud<pcl::PointXYZ>);

pcl::io::loadPCDFile (filename, *cloud);//将命令行的第二个参数传递给filename之后,将filename对应的pcd文件读入
pcl::io::loadPCDFile(filename,*cloud_in);
print_info ("Read pcd file successfully\n");//读入成功标志

//设置sensor_pose和coordinate_frame
Eigen::Affine3f sensorPose;//设置相机位姿
sensorPose.setIdentity(); //成像时遵循的坐标系统
pcl::RangeImage::CoordinateFrame coordinate_frame = pcl::RangeImage::CAMERA_FRAME;
float noiseLevel=0.00;//设置噪声水平
float minRange = 0.0f;//成像时考虑该阈值外的点

pcl::RangeImagePlanar::Ptr rangeImage(new pcl::RangeImagePlanar);
rangeImage->createFromPointCloudWithFixedSize(*cloud,width,height,cx,cy,fx,fy,sensorPose,coordinate_frame);
std::cout << rangeImage << "\n";
//convert unorignized point cloud to orginized point cloud end


//保存深度图像
float *ranges = rangeImage->getRangesArray();
unsigned char* rgb_image = pcl::visualization::FloatImageUtils::getVisualImage(ranges,rangeImage->width,rangeImage->height);
pcl::io::saveRgbPNGFile("rangeImage.png",rgb_image,rangeImage->width,rangeImage->height);
std::cerr<<"rangeImage.png Saved!"<<std::endl;

//viusalization of range image、
//深度图像可视化
pcl::visualization::RangeImageVisualizer range_image_widget ("rangeImage");
range_image_widget.showRangeImage (*rangeImage);
range_image_widget.setWindowTitle("PCL_rangeImage");
//triangulation based on range image
pcl::OrganizedFastMesh<pcl::PointWithRange>::Ptr tri(new pcl::OrganizedFastMesh<pcl::PointWithRange>);
pcl::search::KdTree<pcl::PointWithRange>::Ptr tree (new pcl::search::KdTree<pcl::PointWithRange>);
tree->setInputCloud(rangeImage);//用到了C++赋值兼容原则,派生类的指针可以赋值给基类的指针
pcl::PolygonMesh triangles;//多边形Mesh
tri->setTrianglePixelSize(size);//曲面重建的精细程度
tri->setInputCloud(rangeImage);//设置输入的深度图像
tri->setSearchMethod(tree);//设置搜索方式
tri->setTriangulationType((pcl::OrganizedFastMesh<pcl::PointWithRange>::TriangulationType)type);//设置三角化的类型,是一个枚举类型,将命令行输入的type值进行强制类型转换至对应的三角化的类型
tri->reconstruct(triangles);//重建结果传送至triangles

//可视化
boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer (new pcl::visualization::PCLVisualizer ("PCL"));
//可视化重建结果 ViewPort v1
int v1(0);
viewer->createViewPort(0,0,0.5,1,v1);
viewer->setBackgroundColor(0.5,0.5,0.5,v1);
viewer->addPolygonMesh(triangles,"tin",v1);

//可视化原始点云
int v2(0);
viewer->createViewPort(0.5,0,1,1,v2);
viewer->setBackgroundColor(0,128,0,v2);
pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> color1(cloud_in,190,0,0);
viewer->addPointCloud(cloud_in,color1,"cloud_in",v2);
viewer->addCoordinateSystem();

while (!range_image_widget.wasStopped ()&&!viewer->wasStopped())
{
range_image_widget.spinOnce ();

pcl_sleep (0.01);
viewer->spinOnce ();

}
}

可视化:

(左上为重建后的曲面、右上为原点云、左下为深度图)

PCL 点云转深度图的变换与曲面重建_#include