一、 定义
- 深度图像的每个像素点的灰度值可用于表征场景中某一点距离摄像机的远近。 直接反应了景物可见表面的几何形状。
- 深度图像经过坐标转换可以计算为点云数据,点云数据也可以转换为深度图像。
二、PCL相关函数库
-
所在头文件:#include <pcl/range_image/range_image.h>
-
PCL类
RangeImage是一个工具类,用于在特定视角捕捉的3D场景。
2.1 函数:
template<typename PointCloudType >
void pcl::RangeImage::createFromPointCloud ( const PointCloudType & point_cloud,
float angular_resolution = pcl::deg2rad (0.5f),
float max_angle_width = pcl::deg2rad (360.0f),
float max_angle_height = pcl::deg2rad (180.0f),
const Eigen::Affine3f & sensor_pose = Eigen::Affine3f::Identity (),
RangeImage::CoordinateFrame coordinate_frame = CAMERA_FRAME,
float noise_level = 0.0f,
float min_range = 0.0f,
int border_size = 0
)
参数 | 描述 |
---|---|
point_cloud | 输入的点云数据 |
angular_resolution | 图像中各个像素之间的角差(弧度)。 角差是一次信号与二次信号的相位之差。 |
max_angle_width | 定义传感器水平边界的角度(弧度)。 |
max_angle_height | 定义传感器垂直边界的角度(弧度)。 |
sensor_pose | 传感器姿态的变换矩阵 |
coordinate_frame | 坐标系统 (默认为相机坐标系 CAMERA_FRAME) |
noise_level | 近邻点对查询点距离的影响水平 |
min_range | 最小可视深度 (defaults to 0) |
border_size | 点云边界的尺寸大小 (defaults to 0) |
三、例子分析
int main (int argc, char** argv) {
pcl::PointCloud<pcl::PointXYZ> pointCloud;
// Generate the data 生成表示矩形的点云数据
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;
// We now want to create a range image from the above point cloud, with a 1deg angular resolution
float angularResolution = (float) ( 1.0f * (M_PI/180.0f)); // 1.0 degree in radians
float maxAngleWidth = (float) (360.0f * (M_PI/180.0f)); // 360.0 degree in radians
float maxAngleHeight = (float) (180.0f * (M_PI/180.0f)); // 180.0 degree in radians
Eigen::Affine3f sensorPose = (Eigen::Affine3f)Eigen::Translation3f(0.0f, 0.0f, 0.0f);
pcl::RangeImage::CoordinateFrame coordinate_frame = pcl::RangeImage::CAMERA_FRAME;
float noiseLevel=0.00;
float minRange = 0.0f;
int borderSize = 1;
pcl::RangeImage rangeImage;
rangeImage.createFromPointCloud(pointCloud, angularResolution, maxAngleWidth, maxAngleHeight,
sensorPose, coordinate_frame, noiseLevel, minRange, borderSize);
std::cout << rangeImage << "\n";
}
float angularResolution = (float) ( 1.0f * (M_PI/180.0f)); // 1.0 degree in radians
float maxAngleWidth = (float) (360.0f * (M_PI/180.0f)); // 360.0 degree in radians
float maxAngleHeight = (float) (180.0f * (M_PI/180.0f)); // 180.0 degree in radians
Eigen::Affine3f sensorPose = (Eigen::Affine3f)Eigen::Translation3f(0.0f, 0.0f, 0.0f);
pcl::RangeImage::CoordinateFrame coordinate_frame = pcl::RangeImage::CAMERA_FRAME;
float noiseLevel=0.00;
float minRange = 0.0f;
int borderSize = 1;
angularResolution
表示相邻像素之间的角差是一度。
maxAngleWidth=360 maxAngleHeight=180
,表示我们模拟的距离传感器对周围环境是一个完整的360度视图。 通过调整这个值设置激光器扫描的视角,从而减少计算量。 比如:一个激光只需要描述前方的180度的数据,后面的数据可以忽视,那么设置 maxAngleWidth=180
就足够了。
传感器姿态,包含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的,那么所有深度值小于这个值的点都将被忽略。
minRange = 0.0f 及 minRange=2.0f
结果对比
minRange = 0
minRange=2.0f
当裁剪时,borderSize
大于0会在图像周围留下当前视点看过去不可见点的边界。
pcl::RangeImage rangeImage;
rangeImage.createFromPointCloud(pointCloud, angularResolution, maxAngleWidth, maxAngleHeight,
sensorPose, coordinate_frame, noiseLevel, minRange, borderSize);
深度图像值继承自PointCloud
类 而且 它的点有 x,y,z和range 四个成员。有三类点,可用的真实点是深度大于0, 不可被观察的点是 x=y=z=NAN
并且 range=-INFINITY.
最远距离的点是 x=y=z=NAN
并且 range=INFINITY.
补充:
什么是6DoF
自由度总共有6个,可分成两种不同的类型:平移和旋转。
1. 平移运动
刚体可以在3个自由度中平移:向前/向后,向上/向下,向左/向右。
平移运动
2. 旋转运动
刚体也可以在3个自由度中旋转:纵摇(Pitch)、横摇(Roll)和垂摇(Yaw)。
旋转运动
因此,3种类型的平移自由度+3种类型的旋转自由度 = 6自由度! 在任意一个自由度中,物体可以沿两个“方向”自由运动