💻
Tutorial
  • INTRO
  • Part 0 (개요)
    • README
    • 3D 영상처리
    • [별첨] PCL & PCD란 (100%)
    • chapter02 : PCL 설치 (100%)
    • chapter03 : ROS 실습 준비(100%)
  • Part 1 (초급)
    • README
    • PCL 기반 로봇 비젼
    • [별첨] 파일 생성 및 입출력 (70%)
      • PCL-Cpp (70%)
      • PCL-Python (70%)
      • Open3D-Python (70%)
      • ROS 실습 (90%)
    • Filter
    • [별첨] 샘플링 (70%)
      • 다운샘플링-PCL-Cpp (70%)
      • 다운샘플링-PCL-Python (50%)
      • 업샘플링-PCL-Cpp (70%)
      • ROS 실습 (90%)
    • [별첨] 관심 영역 설정 (70%)
      • PCL-Cpp (70%)
      • PCL-Python (70%)
      • ROS 실습 (90%)
    • [별첨] 노이즈 제거 (70%)
      • PCL-Cpp (70%)
      • PCL-Python (50%)
      • ROS 실습 (90%)
  • Part 2 (중급)
    • README
    • Kd-Tree/Octree Search
    • Chapter03 : Sample Consensus
    • [별첨] 바닥제거 (RANSAC) (70%)
      • PCL-Cpp (70%)
      • PCL-Python (70%)
      • ROS 실습 (90%)
    • 군집화 (70%)
      • Euclidean-PCL-Cpp (70%)
      • Euclidean-PCL-Python (0%)
      • Conditional-Euclidean-PCL-Cpp (50%)
      • DBSCAN-PCL-Python (0%)
      • Region-Growing-PCL-Cpp (50%)
      • Region-Growing-RGB-PCL-Cpp (50%)
      • Min-Cut-PCL-Cpp (50%)
      • Model-Outlier-Removal-PCL-Cpp (50%)
      • Progressive-Morphological-Filter-PCL-Cpp (50%)
    • 포인트 탐색과 배경제거 (60%)
      • Search-Octree-PCL-Cpp (70%)
      • Search-Octree-PCL-Python (70%)
      • Search-Kdtree-PCL-Cpp (70%)
      • Search-Kdtree-PCL-Python (70%)
      • Compression-PCL-Cpp (70%)
      • DetectChanges-PCL-Cpp (50%)
      • DetectChanges-PCL-Python (50%)
    • 특징 찾기 (50%)
      • PFH-PCL-Cpp
      • FPFH-PCL-Cpp
      • Normal-PCL-Cpp (70%)
      • Normal-PCL-Python (80%)
      • Tmp
    • 분류/인식 (30%)
      • 인식-GeometricConsistencyGrouping
      • SVM-RGBD-PCL-Python (70%)
      • SVM-LIDAR-PCL-Python (0%)
      • SVM-ROS (0%)
    • 정합 (70%)
      • ICP-PCL-Cpp (70%)
      • ICP-ROS 실습 (10%)
    • 재구성 (30%)
      • Smoothig-PCL-Cpp (70%)
      • Smoothig-PCL-Python (70%)
      • Triangulation-PCL-Cpp (70%)
  • Part 3 (고급)
    • README
    • 딥러닝 기반 학습 데이터 생성 (0%)
      • PointGAN (90%)
      • AutoEncoder (0%)
    • 딥러닝 기반 샘플링 기법 (0%)
      • DenseLidarNet (50%)
      • Point Cloud Upsampling Network
      • Pseudo-LiDAR
    • 딥러닝 기반 자율주행 탐지 기술 (0%)
    • 딥러닝 기반 자율주행 분류 기술 (0%)
      • Multi3D
      • PointNet
      • VoxelNet (50%)
      • YOLO3D
      • SqueezeSeg
      • butNet
  • Snippets
    • PCL-Snippets
    • PCL-Python-Helper (10%)
    • Lidar Data Augmentation
  • Appendix
    • 시각화Code
    • 시각화툴
    • Annotation툴
    • Point Cloud Libraries (0%)
    • 데이터셋
    • Cling_PCL
    • 참고 자료
    • 작성 계획_Tips
    • 용어집
Powered by GitBook
On this page

Was this helpful?

  1. Part 2 (중급)
  2. 군집화 (70%)

Euclidean-PCL-Cpp (70%)

Previous군집화 (70%)NextEuclidean-PCL-Python (0%)

Last updated 5 years ago

Was this helpful?

코드는 에서 다운로드 가능합니다. 샘플파일은 을 사용하였습니다.

#include <pcl/ModelCoefficients.h>
#include <pcl/point_types.h>
#include <pcl/io/pcd_io.h>
#include <pcl/filters/extract_indices.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/features/normal_3d.h>
#include <pcl/kdtree/kdtree.h>
#include <pcl/sample_consensus/method_types.h>
#include <pcl/sample_consensus/model_types.h>
#include <pcl/segmentation/sac_segmentation.h>
#include <pcl/segmentation/extract_clusters.h>

// Euclidean Cluster Extraction
// http://pointclouds.org/documentation/tutorials/cluster_extraction.php#cluster-extraction

int 
main (int argc, char** argv)
{

  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_f (new pcl::PointCloud<pcl::PointXYZRGB>);

  // *.PCD 파일 읽기 (https://raw.githubusercontent.com/adioshun/gitBook_Tutorial_PCL/master/Intermediate/sample/RANSAC_plane_true.pcd)
  pcl::io::loadPCDFile<pcl::PointXYZRGB> ("RANSAC_plane_true.pcd", *cloud);

  // 포인트수 출력
  std::cout << "PointCloud before filtering has: " << cloud->points.size () << " data points." << std::endl; //*

  // 탐색을 위한 KdTree 오브젝트 생성 //Creating the KdTree object for the search method of the extraction
  pcl::search::KdTree<pcl::PointXYZRGB>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZRGB>);
  tree->setInputCloud (cloud);  //KdTree 생성 


  std::vector<pcl::PointIndices> cluster_indices;       // 군집화된 결과물의 Index 저장, 다중 군집화 객체는 cluster_indices[0] 순으로 저장 
  // 군집화 오브젝트 생성  
  pcl::EuclideanClusterExtraction<pcl::PointXYZRGB> ec;
  ec.setInputCloud (cloud);       // 입력   
  ec.setClusterTolerance (0.02);  // 2cm  
  ec.setMinClusterSize (100);     // 최소 포인트 수 
  ec.setMaxClusterSize (25000);   // 최대 포인트 수
  ec.setSearchMethod (tree);      // 위에서 정의한 탐색 방법 지정 
  ec.extract (cluster_indices);   // 군집화 적용 

  // 클러스터별 정보 수집, 출력, 저장 
  int j = 0;
  for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it)
  {
    pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_cluster (new pcl::PointCloud<pcl::PointXYZRGB>);
    for (std::vector<int>::const_iterator pit = it->indices.begin (); pit != it->indices.end (); ++pit)
     cloud_cluster->points.push_back (cloud->points[*pit]); 
    cloud_cluster->width = cloud_cluster->points.size ();
    cloud_cluster->height = 1;
    cloud_cluster->is_dense = true;

    // 포인트수 출력
    std::cout << "PointCloud representing the Cluster: " << cloud_cluster->points.size () << " data points." << std::endl;

    // 클러스터별 이름 생성 및 저장 
    std::stringstream ss;
    ss << "cloud_cluster_" << j << ".pcd";
    pcl::PCDWriter writer;
    writer.write<pcl::PointXYZRGB> (ss.str (), *cloud_cluster, false); //*
    j++;
  }

  return (0);
}

실행 & 결과

$ PointCloud before filtering has: 23330 data points.
$ PointCloud representing the Cluster: 5981 data points.
$ PointCloud representing the Cluster: 5111 data points.
$ PointCloud representing the Cluster: 4431 data points.
$ PointCloud representing the Cluster: 2768 data points.
$ PointCloud representing the Cluster: 2513 data points.
$ PointCloud representing the Cluster: 1552 data points.
$ PointCloud representing the Cluster: 934 data points.

시각화 & 결과

$ pcl_viewer cloud_cluster_0.pcd 
$ pcl_viewer cloud_cluster_6.pcd

원본(RANSAC_plane_true.pcd)

결과(cloud_cluster_0.pcd)

결과(cloud_cluster_6.pcd)

: Online learning for human classification in 3D LiDAR-based tracking(2017) 에서 활용한 Euclidean clustering 기법

[이곳]
[RANSAC_plane_true.pcd]
Adaptive clustering