๐Ÿ’ป
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. ํŠน์ง• ์ฐพ๊ธฐ (50%)

Normal-PCL-Cpp (70%)

#include <pcl/io/pcd_io.h>
#include <pcl/features/normal_3d.h>
#include <boost/thread/thread.hpp>
#include <pcl/visualization/pcl_visualizer.h>

int
main(int argc, char** argv)
{
    // Object for storing the point cloud.
    pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
    // Object for storing the normals.
    pcl::PointCloud<pcl::Normal>::Ptr normals(new pcl::PointCloud<pcl::Normal>);

    // Read a PCD file from disk.
    pcl::io::loadPCDFile<pcl::PointXYZ>("lobby.pcd", *cloud);

    // Object for normal estimation.
    pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> normalEstimation;
    normalEstimation.setInputCloud(cloud);
    // For every point, use all neighbors in a radius of 3cm.
    normalEstimation.setRadiusSearch(0.03);
    // A kd-tree is a data structure that makes searches efficient. More about it later.
    // The normal estimation object will use it to find nearest neighbors.
    pcl::search::KdTree<pcl::PointXYZ>::Ptr kdtree(new pcl::search::KdTree<pcl::PointXYZ>);
    normalEstimation.setSearchMethod(kdtree);

    // Calculate the normals.
    normalEstimation.compute(*normals);

    // Visualize them.
    boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer(new pcl::visualization::PCLVisualizer("Normals"));
    viewer->addPointCloud<pcl::PointXYZ>(cloud, "cloud");
    // Display one normal out of 20, as a line of length 3cm.
    viewer->addPointCloudNormals<pcl::PointXYZ, pcl::Normal>(cloud, normals, 20, 0.03, "normals");
    while (!viewer->wasStopped())
    {
        viewer->spinOnce(100);
        boost::this_thread::sleep(boost::posix_time::microseconds(100000));
    }
}

normals are stored in "PointCloud" objects

setRadiusSearch(): setKSearch(int K): point's K nearest neighbors to compute the normal

์ถ”ํ›„ Normal ์‹œ์ž‘ํ™” ๋ฐฉ๋ฒ• ์ถ”๊ฐ€

Normal ์ƒ์„ฑ + ๋ณ‘ํ•ฉ + ์ €์žฅ

#include <pcl/point_types.h>
#include <pcl/io/pcd_io.h>
#include <pcl/features/normal_3d.h>
#include <pcl/visualization/pcl_visualizer.h>

// How 3D Features work in PCL
// http://pointclouds.org/documentation/tutorials/how_features_work.php

int
main (int argc, char** argv)
{
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>); // ์ž…๋ ฅ ํฌ์ธํŠธ ํด๋ผ์šฐ๋“œ ์ €์žฅํ•  ์˜ค๋ธŒ์ ํŠธ 
  pcl::PointCloud<pcl::Normal>::Ptr cloud_normals (new pcl::PointCloud<pcl::Normal>); // ๊ณ„์‚ฐ๋œ Normal์„ ์ €์žฅํ•  ์˜ค๋ธŒ์ ํŠธ 
  pcl::PointCloud<pcl::PointNormal> p_n_cloud_c;

  // *.PCD ํŒŒ์ผ ์ฝ๊ธฐ (https://raw.githubusercontent.com/adioshun/gitBook_Tutorial_PCL/master/Beginner/sample/tabletop.pcd)
  pcl::io::loadPCDFile<pcl::PointXYZ> ("tabletop.pcd", *cloud);
  std::cout << "INPUT " << cloud->points.size ()  << std::endl;
  // Create the normal estimation class, and pass the input dataset to it
  pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> ne;
  ne.setInputCloud (cloud);
  pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ> ());
  ne.setSearchMethod (tree);  
  ne.setRadiusSearch (0.03); // Use all neighbors in a sphere of radius 3cm  
                             // setKSearch() ๋ณ€๊ฒฝ ๊ฐ€๋Šฅ 
  ne.compute (*cloud_normals); // Compute the features

  // ํฌ์ธํŠธ์ˆ˜ ์ถœ๋ ฅ  
  std::cout << "NORMAL " << cloud_normals->points.size ()  << std::endl;

  // Copy the point cloud data
  pcl::concatenateFields (*cloud, *cloud_normals, p_n_cloud_c);
  pcl::io::savePCDFile<pcl::PointNormal>("p_n_cloud_c.pcd", p_n_cloud_c);

  std::cerr << "Cloud C: " << std::endl;
  for (std::size_t i = 0; i < 5; ++i)
    std::cerr << "    " <<
      p_n_cloud_c[i].x << " " << p_n_cloud_c[i].y << " " << p_n_cloud_c[i].z << " " <<
      p_n_cloud_c[i].normal[0] << " " << p_n_cloud_c[i].normal[1] << " " << p_n_cloud_c[i].normal[2] << std::endl;



  // Visualize them.
	boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer(new pcl::visualization::PCLVisualizer("Normals"));
	viewer->addPointCloud<pcl::PointXYZ>(cloud, "cloud");
	// Display one normal out of 20, as a line of length 3cm.
	viewer->addPointCloudNormals<pcl::PointXYZ, pcl::Normal>(cloud, cloud_normals, 20, 0.03, "normals");
	while (!viewer->wasStopped())
    {
      viewer->spinOnce(100);
      boost::this_thread::sleep(boost::posix_time::microseconds(100000));
    }
}
PreviousFPFH-PCL-CppNextNormal-PCL-Python (80%)

Last updated 4 years ago

Was this helpful?