• 条件欧几里得聚类


    本教程介绍如何使用pcl::ConditionalEuclideanClustering类:一种基于欧几里得距离和用户可自定义条件对点进行聚类的分割算法。

    此类使用与欧几里得聚类提取区域增长分割基于颜色的区域增长分割相同的贪婪/区域增长/洪水填充方法。与其他类相比,使用此类的优势在于用户现在可以自定义聚类约束(纯欧几里德、平滑度、RGB)。一些缺点包括:没有初始播种系统,没有过度和不足分割控制,以及从主计算循环内部调用条件函数的时间效率较低。

    源码:
    创建:conditional_euclidean_clustering.cpp 文件

    1. 1#include <pcl/point_types.h>
    2. 2#include <pcl/io/pcd_io.h>
    3. 3#include <pcl/console/time.h>
    4. 4
    5. 5#include <pcl/filters/voxel_grid.h>
    6. 6#include <pcl/features/normal_3d.h>
    7. 7#include <pcl/segmentation/conditional_euclidean_clustering.h>
    8. 8
    9. 9typedef pcl::PointXYZI PointTypeIO;
    10. 10typedef pcl::PointXYZINormal PointTypeFull;
    11. 11
    12. 12bool
    13. 13enforceIntensitySimilarity (const PointTypeFull& point_a, const PointTypeFull& point_b, float /*squared_distance*/)
    14. 14{
    15. 15 if (std::abs (point_a.intensity - point_b.intensity) < 5.0f)
    16. 16 return (true);
    17. 17 else
    18. 18 return (false);
    19. 19}
    20. 20
    21. 21bool
    22. 22enforceNormalOrIntensitySimilarity (const PointTypeFull& point_a, const PointTypeFull& point_b, float /*squared_distance*/)
    23. 23{
    24. 24 Eigen::Map<const Eigen::Vector3f> point_a_normal = point_a.getNormalVector3fMap (), point_b_normal = point_b.getNormalVector3fMap ();
    25. 25 if (std::abs (point_a.intensity - point_b.intensity) < 5.0f)
    26. 26 return (true);
    27. 27 if (std::abs (point_a_normal.dot (point_b_normal)) > std::cos (30.0f / 180.0f * static_cast<float> (M_PI)))
    28. 28 return (true);
    29. 29 return (false);
    30. 30}
    31. 31
    32. 32bool
    33. 33customRegionGrowing (const PointTypeFull& point_a, const PointTypeFull& point_b, float squared_distance)
    34. 34{
    35. 35 Eigen::Map<const Eigen::Vector3f> point_a_normal = point_a.getNormalVector3fMap (), point_b_normal = point_b.getNormalVector3fMap ();
    36. 36 if (squared_distance < 10000)
    37. 37 {
    38. 38 if (std::abs (point_a.intensity - point_b.intensity) < 8.0f)
    39. 39 return (true);
    40. 40 if (std::abs (point_a_normal.dot (point_b_normal)) < 0.06)
    41. 41 return (true);
    42. 42 }
    43. 43 else
    44. 44 {
    45. 45 if (std::abs (point_a.intensity - point_b.intensity) < 3.0f)
    46. 46 return (true);
    47. 47 }
    48. 48 return (false);
    49. 49}
    50. 50
    51. 51int
    52. 52main ()
    53. 53{
    54. 54 // Data containers used
    55. 55 pcl::PointCloud<PointTypeIO>::Ptr cloud_in (new pcl::PointCloud<PointTypeIO>), cloud_out (new pcl::PointCloud<PointTypeIO>);
    56. 56 pcl::PointCloud<PointTypeFull>::Ptr cloud_with_normals (new pcl::PointCloud<PointTypeFull>);
    57. 57 pcl::IndicesClustersPtr clusters (new pcl::IndicesClusters), small_clusters (new pcl::IndicesClusters), large_clusters (new pcl::IndicesClusters);
    58. 58 pcl::search::KdTree<PointTypeIO>::Ptr search_tree (new pcl::search::KdTree<PointTypeIO>);
    59. 59 pcl::console::TicToc tt;
    60. 60
    61. 61 // Load the input point cloud
    62. 62 std::cerr << "Loading...\n", tt.tic ();
    63. 63 pcl::io::loadPCDFile ("Statues_4.pcd", *cloud_in);
    64. 64 std::cerr << ">> Done: " << tt.toc () << " ms, " << cloud_in->size () << " points\n";
    65. 65
    66. 66 // Downsample the cloud using a Voxel Grid class
    67. 67 std::cerr << "Downsampling...\n", tt.tic ();
    68. 68 pcl::VoxelGrid<PointTypeIO> vg;
    69. 69 vg.setInputCloud (cloud_in);
    70. 70 vg.setLeafSize (80.0, 80.0, 80.0);
    71. 71 vg.setDownsampleAllData (true);
    72. 72 vg.filter (*cloud_out);
    73. 73 std::cerr << ">> Done: " << tt.toc () << " ms, " << cloud_out->size () << " points\n";
    74. 74
    75. 75 // Set up a Normal Estimation class and merge data in cloud_with_normals
    76. 76 std::cerr << "Computing normals...\n", tt.tic ();
    77. 77 pcl::copyPointCloud (*cloud_out, *cloud_with_normals);
    78. 78 pcl::NormalEstimation<PointTypeIO, PointTypeFull> ne;
    79. 79 ne.setInputCloud (cloud_out);
    80. 80 ne.setSearchMethod (search_tree);
    81. 81 ne.setRadiusSearch (300.0);
    82. 82 ne.compute (*cloud_with_normals);
    83. 83 std::cerr << ">> Done: " << tt.toc () << " ms\n";
    84. 84
    85. 85 // Set up a Conditional Euclidean Clustering class
    86. 86 std::cerr << "Segmenting to clusters...\n", tt.tic ();
    87. 87 pcl::ConditionalEuclideanClustering<PointTypeFull> cec (true);
    88. 88 cec.setInputCloud (cloud_with_normals);
    89. 89 cec.setConditionFunction (&customRegionGrowing);
    90. 90 cec.setClusterTolerance (500.0);
    91. 91 cec.setMinClusterSize (cloud_with_normals->size () / 1000);
    92. 92 cec.setMaxClusterSize (cloud_with_normals->size () / 5);
    93. 93 cec.segment (*clusters);
    94. 94 cec.getRemovedClusters (small_clusters, large_clusters);
    95. 95 std::cerr << ">> Done: " << tt.toc () << " ms\n";
    96. 96
    97. 97 // Using the intensity channel for lazy visualization of the output
    98. 98 for (const auto& small_cluster : (*small_clusters))
    99. 99 for (const auto& j : small_cluster.indices)
    100. 100 (*cloud_out)[j].intensity = -2.0;
    101. 101 for (const auto& large_cluster : (*large_clusters))
    102. 102 for (const auto& j : large_cluster.indices)
    103. 103 (*cloud_out)[j].intensity = +10.0;
    104. 104 for (const auto& cluster : (*clusters))
    105. 105 {
    106. 106 int label = rand () % 8;
    107. 107 for (const auto& j : cluster.indices)
    108. 108 (*cloud_out)[j].intensity = label;
    109. 109 }
    110. 110
    111. 111 // Save the output point cloud
    112. 112 std::cerr << "Saving...\n", tt.tic ();
    113. 113 pcl::io::savePCDFile ("output.pcd", *cloud_out);
    114. 114 std::cerr << ">> Done: " << tt.toc () << " ms\n";
    115. 115
    116. 116 return (0);
    117. 117}

    说明:
    1、头文件

    1. 1#include <pcl/point_types.h>
    2. 2#include <pcl/io/pcd_io.h>
    3. 3#include <pcl/console/time.h>
    4. 4
    5. 5#include <pcl/filters/voxel_grid.h>
    6. 6#include <pcl/features/normal_3d.h>
    7. 7#include <pcl/segmentation/conditional_euclidean_clustering.h>
    8. 8
    9. 9typedef pcl::PointXYZI PointTypeIO;
    10. 10typedef pcl::PointXYZINormal PointTypeFull;

    2、建立对象容器,读取数据

    1. // Data containers used
    2. 55 pcl::PointCloud<PointTypeIO>::Ptr cloud_in (new pcl::PointCloud<PointTypeIO>), cloud_out (new pcl::PointCloud<PointTypeIO>);
    3. 56 pcl::PointCloud<PointTypeFull>::Ptr cloud_with_normals (new pcl::PointCloud<PointTypeFull>);
    4. 57 pcl::IndicesClustersPtr clusters (new pcl::IndicesClusters), small_clusters (new pcl::IndicesClusters), large_clusters (new pcl::IndicesClusters);
    5. 58 pcl::search::KdTree<PointTypeIO>::Ptr search_tree (new pcl::search::KdTree<PointTypeIO>);
    6. 59 pcl::console::TicToc tt;
    7. 60
    8. 61 // Load the input point cloud
    9. 62 std::cerr << "Loading...\n", tt.tic ();
    10. 63 pcl::io::loadPCDFile ("Statues_4.pcd", *cloud_in);
    11. 64 std::cerr << ">> Done: " << tt.toc () << " ms, " << cloud_in->size () << " points\n";

    3、对点云数据进行下采样

    1. 66 // Downsample the cloud using a Voxel Grid class
    2. 67 std::cerr << "Downsampling...\n", tt.tic ();
    3. 68 pcl::VoxelGrid<PointTypeIO> vg;
    4. 69 vg.setInputCloud (cloud_in);
    5. 70 vg.setLeafSize (80.0, 80.0, 80.0);
    6. 71 vg.setDownsampleAllData (true);
    7. 72 vg.filter (*cloud_out);
    8. 73 std::cerr << ">> Done: " << tt.toc () << " ms, " << cloud_out->size () << " points\n";

    4、估计附加点信息的法线,条件欧氏聚类类将用 pcl: : PointXYZINormal 模板化,其中包含 x、 y、 z、强度、法线和曲率信息,以便在条件函数中使用。

    1. 75 // Set up a Normal Estimation class and merge data in cloud_with_normals
    2. 76 std::cerr << "Computing normals...\n", tt.tic ();
    3. 77 pcl::copyPointCloud (*cloud_out, *cloud_with_normals);
    4. 78 pcl::NormalEstimation<PointTypeIO, PointTypeFull> ne;
    5. 79 ne.setInputCloud (cloud_out);
    6. 80 ne.setSearchMethod (search_tree);
    7. 81 ne.setRadiusSearch (300.0);
    8. 82 ne.compute (*cloud_with_normals);
    9. 83 std::cerr << ">> Done: " << tt.toc () << " ms\n";

    5、初始化条件欧几里得聚类,该类初始化为TRUE。这将允许提取太小或太大的簇。如果在没有此选项的情况下初始化类,则可以节省一些计算时间和内存。

    可以使用从 PCLBase 类派生的方法指定类的输入数据,即: setInputCloud 和 setIndices。

    随着集群的增长,它将在集群内部的点和附近的候选点之间评估用户定义的条件

    聚类容差是k-NN搜索的半径,用于查找候选点。

    占云总点数不到0.1%的簇被认为太小。

    占云总点数20%以上的簇被认为太大。

    生成的聚类以pcl::IndicatesClusters格式存储,这是一个索引数组,是输入点云的索引点

    太小的集群或太大的集群不会传递到主输出,而是可以在单独的pcl::IndicatesClusters数据容器中检索,但前提是该类是用TRUE初始化的。

    1. // Set up a Conditional Euclidean Clustering class
    2. std::cerr << "Segmenting to clusters...\n", tt.tic ();
    3. pcl::ConditionalEuclideanClustering<PointTypeFull> cec (true);
    4. cec.setInputCloud (cloud_with_normals);
    5. cec.setConditionFunction (&customRegionGrowing);
    6. cec.setClusterTolerance (500.0);
    7. cec.setMinClusterSize (cloud_with_normals->size () / 1000);
    8. cec.setMaxClusterSize (cloud_with_normals->size () / 5);
    9. cec.segment (*clusters);
    10. cec.getRemovedClusters (small_clusters, large_clusters);
    11. std::cerr << ">> Done: " << tt.toc () << " ms\n";

    6、一些条件函数的示例:

    条件函数的格式是固定的:

    前两个输入参数的类型必须与条件欧几里德聚类中使用的模板类型相同。这些参数将传递当前种子点(第一个参数)和当前候选点(第二个参数)的点信息。

    第三个输入参数需要是浮点数。这个参数将通过种子和候选点之间的平方距离。虽然这些信息也可以使用前两个参数进行计算,但是它已经由底层的最近邻搜索提供,并且可以很容易地用于创建与距离相关的条件函数。

    输出参数需要是一个布尔值。返回 TRUE 将把候选点合并到种子点的簇中。返回 FALSE 将不会通过这个特定的点对合并候选点,但是,这两个点仍然有可能通过不同的点对关系结束在同一个集群中。

    这些示例条件函数只是指示如何使用它们。例如,第二个条件函数将增长簇,只要它们在曲面法线方向上相似或在强度值上相似。这有望将纹理相似的建筑聚类为一个簇,但不会将其与相邻对象合并为同一簇。这将解决强度是否与附近物体足够不同,以及附近物体是否与相同法线共享附近曲面的问题。第三个条件函数类似于第二个条件函数,但根据点之间的距离具有不同的约束。

    1. bool
    2. enforceIntensitySimilarity (const PointTypeFull& point_a, const PointTypeFull& point_b, float /*squared_distance*/)
    3. {
    4. if (std::abs (point_a.intensity - point_b.intensity) < 5.0f)
    5. return (true);
    6. else
    7. return (false);
    8. }
    9. bool
    10. enforceNormalOrIntensitySimilarity (const PointTypeFull& point_a, const PointTypeFull& point_b, float /*squared_distance*/)
    11. {
    12. Eigen::Map<const Eigen::Vector3f> point_a_normal = point_a.getNormalVector3fMap (), point_b_normal = point_b.getNormalVector3fMap ();
    13. if (std::abs (point_a.intensity - point_b.intensity) < 5.0f)
    14. return (true);
    15. if (std::abs (point_a_normal.dot (point_b_normal)) > std::cos (30.0f / 180.0f * static_cast<float> (M_PI)))
    16. return (true);
    17. return (false);
    18. }
    19. bool
    20. customRegionGrowing (const PointTypeFull& point_a, const PointTypeFull& point_b, float squared_distance)
    21. {
    22. Eigen::Map<const Eigen::Vector3f> point_a_normal = point_a.getNormalVector3fMap (), point_b_normal = point_b.getNormalVector3fMap ();
    23. if (squared_distance < 10000)
    24. {
    25. if (std::abs (point_a.intensity - point_b.intensity) < 8.0f)
    26. return (true);
    27. if (std::abs (point_a_normal.dot (point_b_normal)) < 0.06)
    28. return (true);
    29. }
    30. else
    31. {
    32. if (std::abs (point_a.intensity - point_b.intensity) < 3.0f)
    33. return (true);
    34. }
    35. return (false);
    36. }

    7、可视化操作

    1. // Using the intensity channel for lazy visualization of the output
    2. for (const auto& small_cluster : (*small_clusters))
    3. for (const auto& j : small_cluster.indices)
    4. (*cloud_out)[j].intensity = -2.0;
    5. for (const auto& large_cluster : (*large_clusters))
    6. for (const auto& j : large_cluster.indices)
    7. (*cloud_out)[j].intensity = +10.0;
    8. for (const auto& cluster : (*clusters))
    9. {
    10. int label = rand () % 8;
    11. for (const auto& j : cluster.indices)
    12. (*cloud_out)[j].intensity = label;
    13. }

    当用 PCL 的标准 PCD 查看器打开输出点云时,按“5”将切换到强度通道可视化。太小的集群将被染成红色,太大的集群将被染成蓝色,实际的集群/感兴趣的对象将在黄色和青色之间随机着色。

     编译与运行

    1、将以下代码行添加到 CMakeLists.txt

    1. 1cmake_minimum_required(VERSION 3.5 FATAL_ERROR)
    2. 2
    3. 3project(conditional_euclidean_clustering)
    4. 4
    5. 5find_package(PCL 1.7 REQUIRED)
    6. 6
    7. 7include_directories(${PCL_INCLUDE_DIRS})
    8. 8link_directories(${PCL_LIBRARY_DIRS})
    9. 9add_definitions(${PCL_DEFINITIONS})
    10. 10
    11. 11add_executable (conditional_euclidean_clustering conditional_euclidean_clustering.cpp)
    12. 12target_link_libraries (conditional_euclidean_clustering ${PCL_LIBRARIES})

    2、运行

    $ ./conditional_euclidean_clustering

    3、输出

    $ ./pcl_viewer output.pcd

     

  • 相关阅读:
    Windows提权
    彻底卸载52好压
    UniApp项目实践HelloUni
    将SpringBoot项目的jar包注册成service服务的方式启动
    3.3.2 【MySQL】客户端和服务器通信中的字符集
    快速排序 O(nlgn)
    【机器学习】039_合理初始化
    分析方法(二)
    现代 GPU 容易受到新 GPU.zip 侧通道攻击
    面试题什么是分布式垃圾回收(DGC)?它是如何工作的?
  • 原文地址:https://blog.csdn.net/m0_50046535/article/details/125569924