ppf_object_recognition.cpp
Go to the documentation of this file.
00001 #include <pcl/features/ppf.h>
00002 #include <pcl/io/pcd_io.h>
00003 #include <pcl/filters/voxel_grid.h>
00004 #include <pcl/features/normal_3d.h>
00005 #include <pcl/registration/ppf_registration.h>
00006 
00007 #include <pcl/visualization/pcl_visualizer.h>
00008 
00009 #include <pcl/segmentation/sac_segmentation.h>
00010 #include <pcl/filters/extract_indices.h>
00011 #include <pcl/sample_consensus/method_types.h>
00012 #include <pcl/sample_consensus/model_types.h>
00013 
00014 using namespace pcl;
00015 using namespace std;
00016 
00017 const Eigen::Vector4f subsampling_leaf_size (0.02f, 0.02f, 0.02f, 0.0f);
00018 const float normal_estimation_search_radius = 0.05f;
00019 
00020 
00021 PointCloud<PointNormal>::Ptr
00022 subsampleAndCalculateNormals (PointCloud<PointXYZ>::Ptr cloud)
00023 {
00024   PointCloud<PointXYZ>::Ptr cloud_subsampled (new PointCloud<PointXYZ> ());
00025   VoxelGrid<PointXYZ> subsampling_filter;
00026   subsampling_filter.setInputCloud (cloud);
00027   subsampling_filter.setLeafSize (subsampling_leaf_size);
00028   subsampling_filter.filter (*cloud_subsampled);
00029 
00030   PointCloud<Normal>::Ptr cloud_subsampled_normals (new PointCloud<Normal> ());
00031   NormalEstimation<PointXYZ, Normal> normal_estimation_filter;
00032   normal_estimation_filter.setInputCloud (cloud_subsampled);
00033   search::KdTree<PointXYZ>::Ptr search_tree (new search::KdTree<PointXYZ>);
00034   normal_estimation_filter.setSearchMethod (search_tree);
00035   normal_estimation_filter.setRadiusSearch (normal_estimation_search_radius);
00036   normal_estimation_filter.compute (*cloud_subsampled_normals);
00037 
00038   PointCloud<PointNormal>::Ptr cloud_subsampled_with_normals (new PointCloud<PointNormal> ());
00039   concatenateFields (*cloud_subsampled, *cloud_subsampled_normals, *cloud_subsampled_with_normals);
00040 
00041   PCL_INFO ("Cloud dimensions before / after subsampling: %u / %u\n", cloud->points.size (), cloud_subsampled->points.size ());
00042   return cloud_subsampled_with_normals;
00043 }
00044 
00045 int
00046 main (int argc, char** argv)
00047 {
00048   if (argc != 3)
00049   {
00050     PCL_ERROR ("Syntax: ./ppf_object_recognition pcd_model_list pcd_scene\n");
00051     return -1;
00052   }
00053 
00054 
00056   PCL_INFO ("Reading scene ...\n");
00057   PointCloud<PointXYZ>::Ptr cloud_scene (new PointCloud<PointXYZ> ());
00058   PCDReader reader;
00059   reader.read (argv[2], *cloud_scene);
00060   PCL_INFO ("Scene read: %s\n", argv[2]);
00061 
00062   PCL_INFO ("Reading models ...\n");
00063   vector<PointCloud<PointXYZ>::Ptr > cloud_models;
00064   ifstream pcd_file_list (argv[1]);
00065   while (!pcd_file_list.eof())
00066   {
00067     char str[512];
00068     pcd_file_list.getline (str, 512);
00069     PointCloud<PointXYZ>::Ptr cloud (new PointCloud<PointXYZ> ());
00070     reader.read (str, *cloud);
00071     cloud_models.push_back (cloud);
00072     PCL_INFO ("Model read: %s\n", str);
00073   }
00074 
00075   pcl::SACSegmentation<pcl::PointXYZ> seg;
00076   pcl::ExtractIndices<pcl::PointXYZ> extract;
00077   seg.setOptimizeCoefficients (true);
00078   seg.setModelType (pcl::SACMODEL_PLANE);
00079   seg.setMethodType (pcl::SAC_RANSAC);
00080   seg.setMaxIterations (1000);
00081   seg.setDistanceThreshold (0.05);
00082   extract.setNegative (true);
00083   pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients ());
00084   pcl::PointIndices::Ptr inliers (new pcl::PointIndices ());
00085   unsigned nr_points = unsigned (cloud_scene->points.size ());
00086   while (cloud_scene->points.size () > 0.3 * nr_points)
00087   {
00088     seg.setInputCloud (cloud_scene);
00089     seg.segment (*inliers, *coefficients);
00090     PCL_INFO ("Plane inliers: %u\n", inliers->indices.size ());
00091     if (inliers->indices.size () < 50000) break;
00092 
00093     extract.setInputCloud (cloud_scene);
00094     extract.setIndices (inliers);
00095     extract.filter (*cloud_scene);
00096   }
00097 
00098   PointCloud<PointNormal>::Ptr cloud_scene_input = subsampleAndCalculateNormals (cloud_scene);
00099   vector<PointCloud<PointNormal>::Ptr > cloud_models_with_normals;
00100 
00101   PCL_INFO ("Training models ...\n");
00102   vector<PPFHashMapSearch::Ptr> hashmap_search_vector;
00103   for (size_t model_i = 0; model_i < cloud_models.size (); ++model_i)
00104   {
00105     PointCloud<PointNormal>::Ptr cloud_model_input = subsampleAndCalculateNormals (cloud_models[model_i]);
00106     cloud_models_with_normals.push_back (cloud_model_input);
00107 
00108     PointCloud<PPFSignature>::Ptr cloud_model_ppf (new PointCloud<PPFSignature> ());
00109     PPFEstimation<PointNormal, PointNormal, PPFSignature> ppf_estimator;
00110     ppf_estimator.setInputCloud (cloud_model_input);
00111     ppf_estimator.setInputNormals (cloud_model_input);
00112     ppf_estimator.compute (*cloud_model_ppf);
00113 
00114     PPFHashMapSearch::Ptr hashmap_search (new PPFHashMapSearch (12.0f / 180.0f * float (M_PI),
00115                                                                  0.05f));
00116     hashmap_search->setInputFeatureCloud (cloud_model_ppf);
00117     hashmap_search_vector.push_back (hashmap_search);
00118   }
00119 
00120 
00121   visualization::PCLVisualizer viewer ("PPF Object Recognition - Results");
00122   viewer.setBackgroundColor (0, 0, 0);
00123   viewer.addPointCloud (cloud_scene);
00124   viewer.spinOnce (10);
00125   PCL_INFO ("Registering models to scene ...\n");
00126   for (size_t model_i = 0; model_i < cloud_models.size (); ++model_i)
00127   {
00128 
00129     PPFRegistration<PointNormal, PointNormal> ppf_registration;
00130     // set parameters for the PPF registration procedure
00131     ppf_registration.setSceneReferencePointSamplingRate (10);
00132     ppf_registration.setPositionClusteringThreshold (0.2f);
00133     ppf_registration.setRotationClusteringThreshold (30.0f / 180.0f * float (M_PI));
00134     ppf_registration.setSearchMethod (hashmap_search_vector[model_i]);
00135     ppf_registration.setInputSource (cloud_models_with_normals[model_i]);
00136     ppf_registration.setInputTarget (cloud_scene_input);
00137 
00138     PointCloud<PointNormal> cloud_output_subsampled;
00139     ppf_registration.align (cloud_output_subsampled);
00140 
00141     PointCloud<PointXYZ>::Ptr cloud_output_subsampled_xyz (new PointCloud<PointXYZ> ());
00142     for (size_t i = 0; i < cloud_output_subsampled.points.size (); ++i)
00143       cloud_output_subsampled_xyz->points.push_back ( PointXYZ (cloud_output_subsampled.points[i].x, cloud_output_subsampled.points[i].y, cloud_output_subsampled.points[i].z));
00144 
00145 
00146     Eigen::Matrix4f mat = ppf_registration.getFinalTransformation ();
00147     Eigen::Affine3f final_transformation (mat);
00148 
00149 
00150     //  io::savePCDFileASCII ("output_subsampled_registered.pcd", cloud_output_subsampled);
00151 
00152     PointCloud<PointXYZ>::Ptr cloud_output (new PointCloud<PointXYZ> ());
00153     pcl::transformPointCloud (*cloud_models[model_i], *cloud_output, final_transformation);
00154 
00155 
00156     stringstream ss; ss << "model_" << model_i;
00157     visualization::PointCloudColorHandlerRandom<PointXYZ> random_color (cloud_output->makeShared ());
00158     viewer.addPointCloud (cloud_output, random_color, ss.str ());
00159 //    io::savePCDFileASCII (ss.str ().c_str (), *cloud_output);
00160     PCL_INFO ("Showing model %s\n", ss.str ().c_str ());
00161   }
00162 
00163   PCL_INFO ("All models have been registered!\n");
00164 
00165 
00166   while (!viewer.wasStopped ())
00167   {
00168     viewer.spinOnce (100);
00169     boost::this_thread::sleep (boost::posix_time::microseconds (100000));
00170   }
00171 
00172   return 0;
00173 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:31:12