greedy_projection.cpp
Go to the documentation of this file.
00001 #include <pcl/point_types.h>
00002 #include <pcl/io/pcd_io.h>
00003 #include <pcl/kdtree/kdtree_flann.h>
00004 #include <pcl/features/normal_3d.h>
00005 #include <pcl/surface/gp3.h>
00006 
00007 int
00008 main (int argc, char** argv)
00009 {
00010   // Load input file into a PointCloud<T> with an appropriate type
00011   pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
00012   pcl::PCLPointCloud2 cloud_blob;
00013   pcl::io::loadPCDFile ("bun0.pcd", cloud_blob);
00014   pcl::fromPCLPointCloud2 (cloud_blob, *cloud);
00015   //* the data should be available in cloud
00016 
00017   // Normal estimation*
00018   pcl::NormalEstimation<pcl::PointXYZ, pcl::Normal> n;
00019   pcl::PointCloud<pcl::Normal>::Ptr normals (new pcl::PointCloud<pcl::Normal>);
00020   pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
00021   tree->setInputCloud (cloud);
00022   n.setInputCloud (cloud);
00023   n.setSearchMethod (tree);
00024   n.setKSearch (20);
00025   n.compute (*normals);
00026   //* normals should not contain the point normals + surface curvatures
00027 
00028   // Concatenate the XYZ and normal fields*
00029   pcl::PointCloud<pcl::PointNormal>::Ptr cloud_with_normals (new pcl::PointCloud<pcl::PointNormal>);
00030   pcl::concatenateFields (*cloud, *normals, *cloud_with_normals);
00031   //* cloud_with_normals = cloud + normals
00032 
00033   // Create search tree*
00034   pcl::search::KdTree<pcl::PointNormal>::Ptr tree2 (new pcl::search::KdTree<pcl::PointNormal>);
00035   tree2->setInputCloud (cloud_with_normals);
00036 
00037   // Initialize objects
00038   pcl::GreedyProjectionTriangulation<pcl::PointNormal> gp3;
00039   pcl::PolygonMesh triangles;
00040 
00041   // Set the maximum distance between connected points (maximum edge length)
00042   gp3.setSearchRadius (0.025);
00043 
00044   // Set typical values for the parameters
00045   gp3.setMu (2.5);
00046   gp3.setMaximumNearestNeighbors (100);
00047   gp3.setMaximumSurfaceAngle(M_PI/4); // 45 degrees
00048   gp3.setMinimumAngle(M_PI/18); // 10 degrees
00049   gp3.setMaximumAngle(2*M_PI/3); // 120 degrees
00050   gp3.setNormalConsistency(false);
00051 
00052   // Get result
00053   gp3.setInputCloud (cloud_with_normals);
00054   gp3.setSearchMethod (tree2);
00055   gp3.reconstruct (triangles);
00056 
00057   // Additional vertex information
00058   std::vector<int> parts = gp3.getPartIDs();
00059   std::vector<int> states = gp3.getPointStates();
00060 
00061   // Finish
00062   return (0);
00063 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:24:36