5.深度图像

深度图像的获取方法有激光雷达深度成像法,计算机立体视觉成像,坐标测量机法,莫尔条纹法,结构光法等等。

针对深度图像的研究重点主要集中在以下几个方面:

  • 深度图像的分割技术
  • 深度图像的边缘检测技术
  • 基于不同视点的多幅深度图像的配准技术
  • 基于深度数据的三维重建技术
  • 基于三维深度图像的三维目标识别技术
  • 深度图像的多分辨率建模和几何压缩技术等等。

深度图像(Depth Images)也被称为距离影像(Range Image),是指将从图像采集器到场景中各点的距离值作为像素值的图像,它直接反应了景物可见表面的几何形状,利用它可以很方便的解决3D目标描述中的许多问题,深度图像经过点云变换可以计算为点云数据,有规则及有必要信息的点云数据可以反算为深度图像数据。

与点云的区别:

点云:当一束激光照射到物体表面时,所反射的激光会携带方位、距离等信息。若将激光束按照某种轨迹进行扫描,便会边扫描边记录到反射的激光点信息,由 于扫描极为精细,则能够得到大量的激光点,因而就可形成激光点云。点云格式有*.las ;*.pcd; *.txt等。

在PCL 中深度图像与点云最主要的区别在于其近邻的检索方式的不同,并且可以互相转换。

深度图像经过坐标转换可以计算为点云数据;有规则及必要信息的点云数据可以反算为深度图像

1.从点云中获取深度图:

createFromPointCloud(pointCloud, angularResolution, maxAngleWidth, maxAngleHeight,

sensorPose, coordinate_frame, noiseLevel, minRange, borderSize)

  • pointCloud:被检测点云
  • angularResolution=1:邻近的像素点所对应的每个光束之间相差 1°
  • maxAngleWidth=360:进行模拟的距离传感器对周围的环境拥有一个完整的360°视角,无论任何数据集都推荐使用此设置,因为最终获取的深度图像将被裁剪到有空间物体存在的区域范围
  • maxAngleHeight=180: 当传感器后面没有可以观测的点时,设置一个水平视角为180°的激光扫描仪即可,因为需要观察距离传感器前面就可以了。
  • sensorPose: 定义了模拟深度图像获取传感器的6DOF(6自由度)位置,其原始值为横滚角roll、俯仰角 pitch、偏航角 yaw 都为 0
  • coordinate_frame: 设置为CAMERA_FRAME说明系统的X轴是向右的、Y轴是向下的、Z轴是向前的,另外参数值是LASER_FRAME,其X轴向前、Y轴向左、Z轴向上
  • noiseLevel=0: 是指使用一个归一化的 Z缓存区来创建深度图像,如果想让邻近点集都落在同一个像素单元,可以设置一个较高的值,例如 noiseLevel = 0.05 可以理解为深度距离值是通过查询点半径为 5cm 的圆内包含的点用来平均计算而得到的 。
  • minRange=0:如果设置>0则所有模拟器所在位置半径 minRange 内的邻近点都将被忽略,即为盲区。
  • borderSize=1:如果设置>0 ,在裁剪图像时,将在图像周围留下当前视点不可见点的边界 。
#pragma once
#include<pcl/io/pcd_io.h>
#include<pcl/point_types.h>
#include<pcl/range_image/range_image.h>
#include<pcl/visualization/range_image_visualizer.h>
#include<pcl/visualization/pcl_visualizer.h>

//全局参数
float angular_resolution = 0.5f;
pcl::RangeImage::CoordinateFrame coordinate_frame = pcl::RangeImage::CAMERA_FRAME;

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

	//viewer.updateCamera();
}

void main_range_image_show()
{
	angular_resolution = pcl::deg2rad(angular_resolution);

	//读取点云
	pcl::PointCloud<pcl::PointXYZ> ::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
	pcl::PointCloud<pcl::PointXYZ>& point_cloud = *cloud;
	pcl::io::loadPCDFile("maize.pcd", *cloud);
	
	Eigen::Affine3f scene_sensor_pose(Eigen::Affine3f::Identity());
	scene_sensor_pose = Eigen::Affine3f(Eigen::Translation3f(point_cloud.sensor_origin_[0],
		point_cloud.sensor_origin_[1],
		point_cloud.sensor_origin_[2])) *Eigen::Affine3f(point_cloud.sensor_orientation_);


	//从点云创建深度图像对象
	float noise_level = 0.0;
	float min_range = 0.0f;
	int border_size = 1;
	boost::shared_ptr<pcl::RangeImage> range_image_ptr(new pcl::RangeImage);
	pcl::RangeImage& range_image = *range_image_ptr;
	range_image.createFromPointCloud(*cloud, angular_resolution, pcl::deg2rad(360.0f), pcl::deg2rad(180.0f),
		scene_sensor_pose, coordinate_frame, noise_level, min_range, border_size);

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

	//添加坐标系,并对原始点云进行可视化
	//viewer.addCoordinateSystem (1.0f);
	//PointCloudColorHandlerCustom<PointType> point_cloud_color_handler (point_cloud_ptr, 150, 150, 150);
	//viewer.addPointCloud (point_cloud_ptr, point_cloud_color_handler, "original point cloud");

	viewer.initCameraParameters();
	setViewerPose(viewer, range_image.getTransformationToWorldSystem());
	//显示深度图像
	pcl::visualization::RangeImageVisualizer range_image_widget("Range_image");
	range_image_widget.showRangeImage(range_image);
	//主循环
	while (!viewer.wasStopped())
	{
		range_image_widget.spinOnce();
		viewer.spinOnce();
		pcl_sleep(0.01);
		if (1)
		{
			scene_sensor_pose = viewer.getViewerPose();
			range_image.createFromPointCloud(*cloud, angular_resolution, pcl::deg2rad(360.0f), pcl::deg2rad(180.0f), scene_sensor_pose, pcl::RangeImage::LASER_FRAME, noise_level, min_range, border_size);
			range_image_widget.showRangeImage(range_image);
		}
	}
}

 2.从深度图中提取边界

我们对三种不同类型的点感兴趣:

  1. obstacle border:对象边界(属于对象的最外面的可见点)
  2. shadow border:阴影边界(在背景中与遮挡物相邻的点)
  3. Veil points:面纱点集(对象边界边界与阴影边界之间的内插点)

以下是一个典型的激光雷达获得的3D数据对应的点云图:

#pragma once
#include<pcl/point_types.h>
#include<pcl/io/pcd_io.h>
#include<pcl/range_image/range_image.h>
#include<pcl/visualization/range_image_visualizer.h>
#include<pcl/visualization/pcl_visualizer.h>
#include<pcl/features/range_image_border_extractor.h>

float rangular = 0.5f;
pcl::RangeImage::CoordinateFrame coordinateFrame = pcl::RangeImage::CAMERA_FRAME;

void range_image_border_extraction()
{
	pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
	pcl::io::loadPCDFile("rabbit.pcd", *cloud);
	Eigen::Affine3f scene_sensor_pose(Eigen::Affine3f::Identity());
	//从点云创建深度图
	float noise_level = 0.0f;
	float min_range = 0.0f;
	float border_size = 1;
	boost::shared_ptr<pcl::RangeImage>range_image_ptr(new pcl::RangeImage);
	pcl::RangeImage& range_image = *range_image_ptr;
	range_image.createFromPointCloud(*cloud, pcl::deg2rad(rangular), pcl::deg2rad(360.f), pcl::rad2deg(180.0f),
		scene_sensor_pose, coordinateFrame, noise_level, min_range, border_size);
	
	//可视化
	pcl::visualization::PCLVisualizer viewer("3d viewer");
	viewer.setBackgroundColor(1, 1, 1);
	viewer.addCoordinateSystem(1.0f);
	pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ>
		point_cloud_color_handler(cloud, 0, 0, 0);
	viewer.addPointCloud(cloud, point_cloud_color_handler, "original point cloud");

	//提取边界
	pcl::RangeImageBorderExtractor border_extractor(&range_image);
	pcl::PointCloud<pcl::BorderDescription>border_descriptions;
	border_extractor.compute(border_descriptions);

	//在三维浏览器中显示
	pcl::PointCloud<pcl::PointWithRange>::Ptr border_points_ptr(new pcl::PointCloud<pcl::PointWithRange>), veil_points_ptr(new pcl::PointCloud<pcl::PointWithRange>), shadow_points_ptr(new pcl::PointCloud<pcl::PointWithRange>);
	pcl::PointCloud<pcl::PointWithRange>& border_points = *border_points_ptr, & veil_points = *veil_points_ptr, & shadow_points = *shadow_points_ptr;
	for (int y = 0; y < (int)range_image.height; ++y)
	{
		for (int x = 0; x < (int)range_image.width; ++x)
		{
			if (border_descriptions.points[y * range_image.width + x].traits[pcl::BORDER_TRAIT__OBSTACLE_BORDER])
				border_points.points.push_back(range_image.points[y * range_image.width + x]);
			if (border_descriptions.points[y * range_image.width + x].traits[pcl::BORDER_TRAIT__VEIL_POINT])
				veil_points.points.push_back(range_image.points[y * range_image.width + x]);
			if (border_descriptions.points[y * range_image.width + x].traits[pcl::BORDER_TRAIT__SHADOW_BORDER])
				shadow_points.points.push_back(range_image.points[y * range_image.width + x]);
		}
	}
	pcl::visualization::PointCloudColorHandlerCustom<pcl::PointWithRange> border_points_color_handler(border_points_ptr, 0, 255, 0);
	viewer.addPointCloud<pcl::PointWithRange>(border_points_ptr, border_points_color_handler, "border points");
	viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 7, "border points");
	pcl::visualization::PointCloudColorHandlerCustom<pcl::PointWithRange> veil_points_color_handler(veil_points_ptr, 255, 0, 0);
	viewer.addPointCloud<pcl::PointWithRange>(veil_points_ptr, veil_points_color_handler, "veil points");
	viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 7, "veil points");
	pcl::visualization::PointCloudColorHandlerCustom<pcl::PointWithRange> shadow_points_color_handler(shadow_points_ptr, 0, 255, 255);
	viewer.addPointCloud<pcl::PointWithRange>(shadow_points_ptr, shadow_points_color_handler, "shadow points");
	viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 7, "shadow points");
	//-------------------------------------
	// -----在深度图像中显示点集-----
	// ------------------------------------
	pcl::visualization::RangeImageVisualizer* range_image_borders_widget = NULL;
	range_image_borders_widget =
		pcl::visualization::RangeImageVisualizer::getRangeImageBordersWidget(range_image, -std::numeric_limits<float>::infinity(), std::numeric_limits<float>::infinity(), false, border_descriptions, "Range image with borders");
	// -------------------------------------
	//--------------------
	// -----主循环-----
	//--------------------
	while (!viewer.wasStopped())
	{
		range_image_borders_widget->spinOnce();
		viewer.spinOnce(1000);
		//pcl_sleep(0.01);
	}
	system("pause");

}

 

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值