如何从点云创建距离图像(How to create a range image from a point cloud)
该教程演示了如何从点云和传感器位置创建距离图像。首先,生成了一个矩形点云,包含42×36个像素,角分辨率1度。定义了传感器参数,包括最大角度宽度360度、高度180度、噪声水平0.00、最小范围0.00和边框大小1。使用PCL库中的RangeImage::createFromPointCloud函数创建了范围图像,并输出了结果。
本教程展示基于点云和给定传感器位置的距离图像创建方法。该代码生成了一个位于观察者前方的矩形示例点云。
注释说明
代码主体
代码结束
#include <pcl/range_image/range_image.h>
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";
}
#说明
让我们看看这个部分:
#include <pcl/range_image/range_image.h>
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;
This contains the necessary range image header, and the main is initiated and the point cloud is created, representing a rectangle.
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;
这部分指定了我们想要创建的距离图像的参数。
角分辨率设定为1度,这意味着相邻像素所代表的光束之间相差一个度数。
maxAngleWidth = 360和maxAngleHeight = 180意味着我们模拟的距离传感器具有完整的360度环绕视图。您始终可以使用此设置,因为范围图像只会被裁剪以适应自动检测到的区域。然而,您可以通过减少这些值来节省计算资源。例如,对于面向前方具有180度视界的激光扫描仪,在传感器后方无法观察到任何点,因此将maxAngleWidth设置为180度就足够了。
sensorPose将虚拟传感器的6自由度位置定义为roll = pitch = yaw = 0的原点。
coordinate_frame = CAMERA_FRAME告诉系统,坐标系中x轴向右,y轴向下,z轴向前。另一种选择是LASER_FRAME,其中x轴向前,y轴向左,z轴向上。
对于noiseLevel = 0,范围图像是通过正常的z缓冲区创建的。然而,如果你希望平均落在同一单元格中的点数,你可以使用更高的noiseLevel值。例如,noiseLevel = 0.05意味着所有与最近点距离小于5cm的点都会用于计算范围。
如果minRange大于0,所有距离较近的点都将被忽略。
borderSize大于0会在裁剪图像时在周围留下未观察点的边框。
pcl::RangeImage rangeImage;
rangeImage.createFromPointCloud(pointCloud, angularResolution, maxAngleWidth, maxAngleHeight,sensorPose, coordinate_frame, noiseLevel, minRange, borderSize);
std::cout << rangeImage << "\n";
剩余的代码将基于给定的参数生成距离图像,并在控制台输出相关信息内容。
范围图像源自PointCloud类,其中,点包含成员x、y、z以及范围属性。该图像包含三种不同的观点。有效点的范围值大于零。未观察点的坐标x、y、z均为NAN,且范围值为负无穷。远程点的坐标x、y、z均为NAN,且范围值为正无穷。
#编译和运行程序
将以下行添加到您的CMakeLists.txt文件中:
cmake_minimum_required(VERSION 2.6 FATAL_ERROR)
project(range_image_creation)
find_package(PCL 1.2 REQUIRED)
include_directories(${PCL_INCLUDE_DIRS})
link_directories(${PCL_LIBRARY_DIRS})
add_definitions(${PCL_DEFINITIONS})
add_executable (range_image_creation range_image_creation.cpp)
target_link_libraries (range_image_creation ${PCL_LIBRARIES})
在创建可执行文件后,您可以运行它。简单地做:
./range_image_creation
你应该看到以下内容:
range image of size 42x36 with angular resolution 1deg/pixel and 1512 points
