pcl--第二节 深度图像RangeImage

目前深度图像的获取方法有激光雷达深度成像法,计算机立体视觉成像,坐标测量机法,莫尔条纹法,结构光法等等,针对深度图像的研究重点主要集中在以下几个方面,

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

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

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

pcl--第二节 深度图像RangeImage_第1张图片

/* \author Bastian Steder */

#include 

#include 
#include 
#include 
#include 
#include 
#include 
#include  // for getFilenameWithoutExtension

typedef pcl::PointXYZ PointType;

// --------------------
// -----Parameters-----
// --------------------
float angular_resolution = 0.5f;
pcl::RangeImage::CoordinateFrame coordinate_frame = pcl::RangeImage::CAMERA_FRAME;
bool setUnseenToMaxRange = false;

// --------------
// -----Help-----
// --------------
void
printUsage(const char* progName)
{
    std::cout << "\n\nUsage: " << progName << " [options] \n\n"
        << "Options:\n"
        << "-------------------------------------------\n"
        << "-r    angular resolution in degrees (default " << angular_resolution << ")\n"
        << "-c      coordinate frame (default " << (int)coordinate_frame << ")\n"
        << "-m           Treat all unseen points to max range\n"
        << "-h           this help\n"
        << "\n\n";
}

// --------------
// -----Main-----
// --------------
int
main(int argc, char** argv)
{
    // --------------------------------------
    // -----Parse Command Line Arguments-----
    // --------------------------------------
    if (pcl::console::find_argument(argc, argv, "-h") >= 0)
    {
        printUsage(argv[0]);
        return 0;
    }
    if (pcl::console::find_argument(argc, argv, "-m") >= 0)
    {
        setUnseenToMaxRange = true;
        std::cout << "Setting unseen values in range image to maximum range readings.\n";
    }
    int tmp_coordinate_frame;
    if (pcl::console::parse(argc, argv, "-c", tmp_coordinate_frame) >= 0)
    {
        coordinate_frame = pcl::RangeImage::CoordinateFrame(tmp_coordinate_frame);
        std::cout << "Using coordinate frame " << (int)coordinate_frame << ".\n";
    }
    if (pcl::console::parse(argc, argv, "-r", angular_resolution) >= 0)
        std::cout << "Setting angular resolution to " << angular_resolution << "deg.\n";
    angular_resolution = pcl::deg2rad(angular_resolution);

    // ------------------------------------------------------------------
    // -----Read pcd file or create example point cloud if not given-----
    // ------------------------------------------------------------------
    pcl::PointCloud::Ptr point_cloud_ptr(new pcl::PointCloud);
    pcl::PointCloud& point_cloud = *point_cloud_ptr;
    pcl::PointCloud far_ranges;
    Eigen::Affine3f scene_sensor_pose(Eigen::Affine3f::Identity());
    std::vector pcd_filename_indices = pcl::console::parse_file_extension_argument(argc, argv, "pcd");
    if (!pcd_filename_indices.empty())
    {
        std::string filename = argv[pcd_filename_indices[0]];
        if (pcl::io::loadPCDFile(filename, point_cloud) == -1)
        {
            std::cout << "Was not able to open file \"" << filename << "\".\n";
            printUsage(argv[0]);
            return 0;
        }
        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_);

        std::string far_ranges_filename = pcl::getFilenameWithoutExtension(filename) + "_far_ranges.pcd";
        if (pcl::io::loadPCDFile(far_ranges_filename.c_str(), far_ranges) == -1)
            std::cout << "Far ranges file \"" << far_ranges_filename << "\" does not exists.\n";
    }
    else
    {
        std::cout << "\nNo *.pcd file given => Generating example point cloud.\n\n";
        for (float x = -0.5f; x <= 0.5f; x += 0.01f)
        {
            for (float y = -0.5f; y <= 0.5f; y += 0.01f)
            {
                PointType point;  point.x = x;  point.y = y;  point.z = 2.0f - y;
                point_cloud.push_back(point);
            }
        }
        point_cloud.width = point_cloud.size();  point_cloud.height = 1;
    }

    // -----------------------------------------------
    // -----Create RangeImage from the PointCloud-----
    // -----------------------------------------------
    float noise_level = 0.0;
    float min_range = 0.0f;
    int border_size = 1;
    pcl::RangeImage::Ptr range_image_ptr(new pcl::RangeImage);
    pcl::RangeImage& range_image = *range_image_ptr;
    range_image.createFromPointCloud(point_cloud, angular_resolution, pcl::deg2rad(360.0f), pcl::deg2rad(180.0f),
        scene_sensor_pose, coordinate_frame, noise_level, min_range, border_size);
    range_image.integrateFarRanges(far_ranges);
    if (setUnseenToMaxRange)
        range_image.setUnseenToMaxRange();

    // --------------------------------------------
    // -----Open 3D viewer and add point cloud-----
    // --------------------------------------------
    pcl::visualization::PCLVisualizer viewer("3D Viewer");
    viewer.setBackgroundColor(1, 1, 1);
    viewer.addCoordinateSystem(1.0f, "global");
    pcl::visualization::PointCloudColorHandlerCustom point_cloud_color_handler(point_cloud_ptr, 0, 0, 0);
    viewer.addPointCloud(point_cloud_ptr, point_cloud_color_handler, "original point cloud");
    //PointCloudColorHandlerCustom range_image_color_handler (range_image_ptr, 150, 150, 150);
    //viewer.addPointCloud (range_image_ptr, range_image_color_handler, "range image");
    //viewer.setPointCloudRenderingProperties (PCL_VISUALIZER_POINT_SIZE, 2, "range image");

    // -------------------------
    // -----Extract borders-----
    // -------------------------
    pcl::RangeImageBorderExtractor border_extractor(&range_image);
    pcl::PointCloud border_descriptions;
    border_extractor.compute(border_descriptions);

    // ----------------------------------
    // -----Show points in 3D viewer-----
    // ----------------------------------
    pcl::PointCloud::Ptr border_points_ptr(new pcl::PointCloud),
        veil_points_ptr(new pcl::PointCloud),
        shadow_points_ptr(new pcl::PointCloud);
    pcl::PointCloud& 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[y * range_image.width + x].traits[pcl::BORDER_TRAIT__OBSTACLE_BORDER])
                border_points.push_back(range_image[y * range_image.width + x]);
            if (border_descriptions[y * range_image.width + x].traits[pcl::BORDER_TRAIT__VEIL_POINT])
                veil_points.push_back(range_image[y * range_image.width + x]);
            if (border_descriptions[y * range_image.width + x].traits[pcl::BORDER_TRAIT__SHADOW_BORDER])
                shadow_points.push_back(range_image[y * range_image.width + x]);
        }
    }
    pcl::visualization::PointCloudColorHandlerCustom border_points_color_handler(border_points_ptr, 0, 255, 0);
    viewer.addPointCloud(border_points_ptr, border_points_color_handler, "border points");
    viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 7, "border points");
    pcl::visualization::PointCloudColorHandlerCustom veil_points_color_handler(veil_points_ptr, 255, 0, 0);
    viewer.addPointCloud(veil_points_ptr, veil_points_color_handler, "veil points");
    viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 7, "veil points");
    pcl::visualization::PointCloudColorHandlerCustom shadow_points_color_handler(shadow_points_ptr, 0, 255, 255);
    viewer.addPointCloud(shadow_points_ptr, shadow_points_color_handler, "shadow points");
    viewer.setPointCloudRenderingProperties(pcl::visualization::PCL_VISUALIZER_POINT_SIZE, 7, "shadow points");

    //-------------------------------------
    // -----Show points on range image-----
    // ------------------------------------
    pcl::visualization::RangeImageVisualizer* range_image_borders_widget = NULL;
    range_image_borders_widget =
        pcl::visualization::RangeImageVisualizer::getRangeImageBordersWidget(range_image, -std::numeric_limits::infinity(), std::numeric_limits::infinity(), false,
            border_descriptions, "Range image with borders");
    // -------------------------------------


    //--------------------
    // -----Main loop-----
    //--------------------
    while (!viewer.wasStopped())
    {
        range_image_borders_widget->spinOnce();
        viewer.spinOnce();
        pcl_sleep(0.01);
    }
}

你可能感兴趣的:(计算机视觉,图像处理,人工智能)