tutorial.cpp
Go to the documentation of this file.
00001 #include <vector>
00002 #include <string>
00003 #include <sstream>
00004 #include <pcl/io/pcd_io.h>
00005 #include <pcl/registration/transforms.h>
00006 #include <pcl/visualization/pcl_visualizer.h>
00007 #include <pcl/keypoints/sift_keypoint.h>
00008 #include <pcl/keypoints/harris_keypoint3D.h>
00009 #include <pcl/ModelCoefficients.h>
00010 #include <pcl/sample_consensus/method_types.h>
00011 #include <pcl/sample_consensus/model_types.h>
00012 #include <pcl/segmentation/sac_segmentation.h>
00013 #include <pcl/search/kdtree.h>
00014 #include <pcl/segmentation/extract_clusters.h>
00015 #include <pcl/features/fpfh_omp.h>
00016 #include <pcl/features/pfh.h>
00017 #include <pcl/features/pfhrgb.h>
00018 #include <pcl/features/3dsc.h>
00019 #include <pcl/features/shot_omp.h>
00020 #include <pcl/kdtree/kdtree_flann.h>
00021 #include <pcl/kdtree/impl/kdtree_flann.hpp>
00022 #include <pcl/registration/transformation_estimation_svd.h>
00023 #include <pcl/registration/icp.h>
00024 #include <pcl/registration/correspondence_rejection_sample_consensus.h>
00025 #include <pcl/common/transforms.h>
00026 #include <pcl/surface/grid_projection.h>
00027 #include <pcl/surface/gp3.h>
00028 #include <pcl/surface/marching_cubes_hoppe.h>
00029 
00030 template<typename FeatureType>
00031 class ICCVTutorial
00032 {
00033   public:
00034     ICCVTutorial (boost::shared_ptr<pcl::Keypoint<pcl::PointXYZRGB, pcl::PointXYZI> > keypoint_detector,
00035                   typename pcl::Feature<pcl::PointXYZRGB, FeatureType>::Ptr feature_extractor,
00036                   boost::shared_ptr<pcl::PCLSurfaceBase<pcl::PointXYZRGBNormal> > surface_reconstructor,
00037                   typename pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr source,
00038                   typename pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr target);
00039     
00043     void run ();
00044   protected:
00050     void segmentation (typename pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr input, typename pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented) const;
00051     
00057     void detectKeypoints (typename pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr input, pcl::PointCloud<pcl::PointXYZI>::Ptr keypoints) const;
00058     
00065     void extractDescriptors (typename pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr input, typename pcl::PointCloud<pcl::PointXYZI>::Ptr keypoints, typename pcl::PointCloud<FeatureType>::Ptr features);
00066     
00073     void findCorrespondences (typename pcl::PointCloud<FeatureType>::Ptr source, typename pcl::PointCloud<FeatureType>::Ptr target, std::vector<int>& correspondences) const;
00074     
00078     void filterCorrespondences ();
00079     
00083     void determineInitialTransformation ();
00084     
00088     void determineFinalTransformation ();
00089 
00093     void reconstructSurface ();
00094 
00100     void keyboard_callback (const pcl::visualization::KeyboardEvent& event, void* cookie);
00101     
00102   private:
00103     pcl::visualization::PCLVisualizer visualizer_;
00104     pcl::PointCloud<pcl::PointXYZI>::Ptr source_keypoints_;
00105     pcl::PointCloud<pcl::PointXYZI>::Ptr target_keypoints_;
00106     boost::shared_ptr<pcl::Keypoint<pcl::PointXYZRGB, pcl::PointXYZI> > keypoint_detector_;
00107     typename pcl::Feature<pcl::PointXYZRGB, FeatureType>::Ptr feature_extractor_;
00108     boost::shared_ptr<pcl::PCLSurfaceBase<pcl::PointXYZRGBNormal> > surface_reconstructor_;
00109     typename pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr source_;
00110     typename pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr target_;
00111     typename pcl::PointCloud<pcl::PointXYZRGB>::Ptr source_segmented_;
00112     typename pcl::PointCloud<pcl::PointXYZRGB>::Ptr target_segmented_;
00113     typename pcl::PointCloud<pcl::PointXYZRGB>::Ptr source_transformed_;
00114     typename pcl::PointCloud<pcl::PointXYZRGB>::Ptr source_registered_;
00115     typename pcl::PolygonMesh surface_;
00116     typename pcl::PointCloud<FeatureType>::Ptr source_features_;
00117     typename pcl::PointCloud<FeatureType>::Ptr target_features_;
00118     std::vector<int> source2target_;
00119     std::vector<int> target2source_;
00120     pcl::CorrespondencesPtr correspondences_;
00121     Eigen::Matrix4f initial_transformation_matrix_;
00122     Eigen::Matrix4f transformation_matrix_;
00123     bool show_source2target_;
00124     bool show_target2source_;
00125     bool show_correspondences;
00126 };
00127 
00128 template<typename FeatureType>
00129 ICCVTutorial<FeatureType>::ICCVTutorial(boost::shared_ptr<pcl::Keypoint<pcl::PointXYZRGB, pcl::PointXYZI> >keypoint_detector,
00130                                         typename pcl::Feature<pcl::PointXYZRGB, FeatureType>::Ptr feature_extractor,
00131                                         boost::shared_ptr<pcl::PCLSurfaceBase<pcl::PointXYZRGBNormal> > surface_reconstructor,
00132                                         typename pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr source,
00133                                         typename pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr target)
00134 : source_keypoints_ (new pcl::PointCloud<pcl::PointXYZI> ())
00135 , target_keypoints_ (new pcl::PointCloud<pcl::PointXYZI> ())
00136 , keypoint_detector_ (keypoint_detector)
00137 , feature_extractor_ (feature_extractor)
00138 , surface_reconstructor_ (surface_reconstructor)
00139 , source_ (source)
00140 , target_ (target)
00141 , source_segmented_ (new pcl::PointCloud<pcl::PointXYZRGB>)
00142 , target_segmented_ (new pcl::PointCloud<pcl::PointXYZRGB>)
00143 , source_transformed_ (new pcl::PointCloud<pcl::PointXYZRGB>)
00144 , source_registered_ (new pcl::PointCloud<pcl::PointXYZRGB>)
00145 , source_features_ (new pcl::PointCloud<FeatureType>)
00146 , target_features_ (new pcl::PointCloud<FeatureType>)
00147 , correspondences_ (new pcl::Correspondences)
00148 , show_source2target_ (false)
00149 , show_target2source_ (false)
00150 , show_correspondences (false)
00151 {
00152   visualizer_.registerKeyboardCallback(&ICCVTutorial::keyboard_callback, *this, 0);
00153   
00154   segmentation (source_, source_segmented_);
00155   segmentation (target_, target_segmented_);  
00156   
00157   detectKeypoints (source_segmented_, source_keypoints_);
00158   detectKeypoints (target_segmented_, target_keypoints_);
00159   
00160   extractDescriptors (source_segmented_, source_keypoints_, source_features_);
00161   extractDescriptors (target_segmented_, target_keypoints_, target_features_);
00162   
00163   findCorrespondences (source_features_, target_features_, source2target_);
00164   findCorrespondences (target_features_, source_features_, target2source_);
00165   
00166   filterCorrespondences ();
00167   
00168   determineInitialTransformation ();
00169   determineFinalTransformation ();
00170   
00171   reconstructSurface ();
00172 }
00173 
00174 template<typename FeatureType>
00175 void ICCVTutorial<FeatureType>::segmentation (typename pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr source, typename pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented) const
00176 {
00177   cout << "segmentation..." << std::flush;
00178   // fit plane and keep points above that plane
00179   pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients);
00180   pcl::PointIndices::Ptr inliers (new pcl::PointIndices);
00181   // Create the segmentation object
00182   pcl::SACSegmentation<pcl::PointXYZRGB> seg;
00183   // Optional
00184   seg.setOptimizeCoefficients (true);
00185   // Mandatory
00186   seg.setModelType (pcl::SACMODEL_PLANE);
00187   seg.setMethodType (pcl::SAC_RANSAC);
00188   seg.setDistanceThreshold (0.02);
00189 
00190   seg.setInputCloud (source);
00191   seg.segment (*inliers, *coefficients);
00192   
00193   pcl::ExtractIndices<pcl::PointXYZRGB> extract;
00194   extract.setInputCloud (source);
00195   extract.setIndices (inliers);
00196   extract.setNegative (true);
00197 
00198   extract.filter (*segmented);
00199   std::vector<int> indices;
00200   pcl::removeNaNFromPointCloud(*segmented, *segmented, indices);
00201   cout << "OK" << endl;
00202   
00203   cout << "clustering..." << std::flush;
00204   // euclidean clustering
00205   typename pcl::search::KdTree<pcl::PointXYZRGB>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZRGB>);
00206   tree->setInputCloud (segmented);
00207 
00208   std::vector<pcl::PointIndices> cluster_indices;
00209   pcl::EuclideanClusterExtraction<pcl::PointXYZRGB> clustering;
00210   clustering.setClusterTolerance (0.02); // 2cm
00211   clustering.setMinClusterSize (1000);
00212   clustering.setMaxClusterSize (250000);
00213   clustering.setSearchMethod (tree);
00214   clustering.setInputCloud(segmented);
00215   clustering.extract (cluster_indices);
00216   
00217   if (cluster_indices.size() > 0)//use largest cluster
00218   {
00219     cout << cluster_indices.size() << " clusters found";
00220     if (cluster_indices.size() > 1)
00221       cout <<" Using largest one...";
00222     cout << endl;
00223     typename pcl::IndicesPtr indices (new std::vector<int>);
00224     *indices = cluster_indices[0].indices;
00225     extract.setInputCloud (segmented);
00226     extract.setIndices (indices);
00227     extract.setNegative (false);
00228 
00229     extract.filter (*segmented);
00230   }
00231 }
00232 
00233 template<typename FeatureType>
00234 void ICCVTutorial<FeatureType>::detectKeypoints (typename pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr input, pcl::PointCloud<pcl::PointXYZI>::Ptr keypoints) const
00235 {
00236   cout << "keypoint detection..." << std::flush;
00237   keypoint_detector_->setInputCloud(input);
00238   keypoint_detector_->setSearchSurface(input);
00239   keypoint_detector_->compute(*keypoints);
00240   cout << "OK. keypoints found: " << keypoints->points.size() << endl;
00241 }
00242 
00243 template<typename FeatureType>
00244 void ICCVTutorial<FeatureType>::extractDescriptors (typename pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr input, typename pcl::PointCloud<pcl::PointXYZI>::Ptr keypoints, typename pcl::PointCloud<FeatureType>::Ptr features)
00245 {
00246   typename pcl::PointCloud<pcl::PointXYZRGB>::Ptr kpts(new pcl::PointCloud<pcl::PointXYZRGB>);
00247   kpts->points.resize(keypoints->points.size());
00248   
00249   pcl::copyPointCloud(*keypoints, *kpts);
00250           
00251   typename pcl::FeatureFromNormals<pcl::PointXYZRGB, pcl::Normal, FeatureType>::Ptr feature_from_normals = boost::dynamic_pointer_cast<pcl::FeatureFromNormals<pcl::PointXYZRGB, pcl::Normal, FeatureType> > (feature_extractor_);
00252   
00253   feature_extractor_->setSearchSurface(input);
00254   feature_extractor_->setInputCloud(kpts);
00255   
00256   if (feature_from_normals)
00257   //if (boost::dynamic_pointer_cast<typename pcl::FeatureFromNormals<pcl::PointXYZRGB, pcl::Normal, FeatureType> > (feature_extractor_))
00258   {
00259     cout << "normal estimation..." << std::flush;
00260     typename pcl::PointCloud<pcl::Normal>::Ptr normals (new  pcl::PointCloud<pcl::Normal>);
00261     pcl::NormalEstimation<pcl::PointXYZRGB, pcl::Normal> normal_estimation;
00262     normal_estimation.setSearchMethod (pcl::search::Search<pcl::PointXYZRGB>::Ptr (new pcl::search::KdTree<pcl::PointXYZRGB>));
00263     normal_estimation.setRadiusSearch (0.01);
00264     normal_estimation.setInputCloud (input);
00265     normal_estimation.compute (*normals);
00266     feature_from_normals->setInputNormals(normals);
00267     cout << "OK" << endl;
00268   }
00269 
00270   cout << "descriptor extraction..." << std::flush;
00271   feature_extractor_->compute (*features);
00272   cout << "OK" << endl;
00273 }
00274 
00275 template<typename FeatureType>
00276 void ICCVTutorial<FeatureType>::findCorrespondences (typename pcl::PointCloud<FeatureType>::Ptr source, typename pcl::PointCloud<FeatureType>::Ptr target, std::vector<int>& correspondences) const
00277 {
00278   cout << "correspondence assignment..." << std::flush;
00279   correspondences.resize (source->size());
00280 
00281   // Use a KdTree to search for the nearest matches in feature space
00282   pcl::KdTreeFLANN<FeatureType> descriptor_kdtree;
00283   descriptor_kdtree.setInputCloud (target);
00284 
00285   // Find the index of the best match for each keypoint, and store it in "correspondences_out"
00286   const int k = 1;
00287   std::vector<int> k_indices (k);
00288   std::vector<float> k_squared_distances (k);
00289   for (size_t i = 0; i < source->size (); ++i)
00290   {
00291     descriptor_kdtree.nearestKSearch (*source, i, k, k_indices, k_squared_distances);
00292     correspondences[i] = k_indices[0];
00293   }
00294   cout << "OK" << endl;
00295 }
00296 
00297 template<typename FeatureType>
00298 void ICCVTutorial<FeatureType>::filterCorrespondences ()
00299 {
00300   cout << "correspondence rejection..." << std::flush;
00301   std::vector<std::pair<unsigned, unsigned> > correspondences;
00302   for (unsigned cIdx = 0; cIdx < source2target_.size (); ++cIdx)
00303     if (target2source_[source2target_[cIdx]] == cIdx)
00304       correspondences.push_back(std::make_pair(cIdx, source2target_[cIdx]));
00305   
00306   correspondences_->resize (correspondences.size());
00307   for (unsigned cIdx = 0; cIdx < correspondences.size(); ++cIdx)
00308   {
00309     (*correspondences_)[cIdx].index_query = correspondences[cIdx].first;
00310     (*correspondences_)[cIdx].index_match = correspondences[cIdx].second;
00311   }
00312   
00313   pcl::registration::CorrespondenceRejectorSampleConsensus<pcl::PointXYZI> rejector;
00314   rejector.setInputCloud(source_keypoints_);
00315   rejector.setTargetCloud(target_keypoints_);
00316   rejector.setInputCorrespondences(correspondences_);
00317   rejector.getCorrespondences(*correspondences_);
00318   cout << "OK" << endl;
00319 }
00320 
00321 template<typename FeatureType>
00322 void ICCVTutorial<FeatureType>::determineInitialTransformation ()
00323 {
00324   cout << "initial alignment..." << std::flush;
00325   pcl::registration::TransformationEstimation<pcl::PointXYZI, pcl::PointXYZI>::Ptr transformation_estimation (new pcl::registration::TransformationEstimationSVD<pcl::PointXYZI, pcl::PointXYZI>);
00326   
00327   transformation_estimation->estimateRigidTransformation (*source_keypoints_, *target_keypoints_, *correspondences_, initial_transformation_matrix_);
00328   
00329   pcl::transformPointCloud(*source_segmented_, *source_transformed_, initial_transformation_matrix_);
00330   cout << "OK" << endl;
00331 }
00332 
00333 template<typename FeatureType>
00334 void ICCVTutorial<FeatureType>::determineFinalTransformation ()
00335 {
00336   cout << "final registration..." << std::flush;
00337   pcl::Registration<pcl::PointXYZRGB, pcl::PointXYZRGB>::Ptr registration (new pcl::IterativeClosestPoint<pcl::PointXYZRGB, pcl::PointXYZRGB>);
00338   registration->setInputCloud(source_transformed_);
00339   //registration->setInputCloud(source_segmented_);
00340   registration->setInputTarget (target_segmented_);
00341   registration->setMaxCorrespondenceDistance(0.05);
00342   registration->setRANSACOutlierRejectionThreshold (0.05);
00343   registration->setTransformationEpsilon (0.000001);
00344   registration->setMaximumIterations (1000);
00345   registration->align(*source_registered_);
00346   transformation_matrix_ = registration->getFinalTransformation();
00347   cout << "OK" << endl;
00348 }
00349 
00350 template<typename FeatureType>
00351 void ICCVTutorial<FeatureType>::reconstructSurface ()
00352 {
00353   cout << "surface reconstruction..." << std::flush;
00354   // merge the transformed and the target point cloud
00355   pcl::PointCloud<pcl::PointXYZRGB>::Ptr merged (new pcl::PointCloud<pcl::PointXYZRGB>);
00356   *merged = *source_transformed_;
00357   *merged += *target_segmented_;
00358   
00359   // apply grid filtering to reduce amount of points as well as to make them uniform distributed
00360   pcl::VoxelGrid<pcl::PointXYZRGB> voxel_grid;
00361   voxel_grid.setInputCloud(merged);
00362   voxel_grid.setLeafSize(0.002, 0.002, 0.002);
00363   voxel_grid.setDownsampleAllData(true);
00364   voxel_grid.filter(*merged);
00365 
00366   pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr vertices (new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00367   pcl::copyPointCloud(*merged, *vertices);
00368 
00369   pcl::NormalEstimation<pcl::PointXYZRGB, pcl::PointXYZRGBNormal> normal_estimation;
00370   normal_estimation.setSearchMethod (pcl::search::Search<pcl::PointXYZRGB>::Ptr (new pcl::search::KdTree<pcl::PointXYZRGB>));
00371   normal_estimation.setRadiusSearch (0.01);
00372   normal_estimation.setInputCloud (merged);
00373   normal_estimation.compute (*vertices);
00374   
00375   pcl::search::KdTree<pcl::PointXYZRGBNormal>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZRGBNormal>);
00376   tree->setInputCloud (vertices);
00377 
00378   surface_reconstructor_->setSearchMethod(tree);
00379   surface_reconstructor_->setInputCloud(vertices);
00380   surface_reconstructor_->reconstruct(surface_);
00381   cout << "OK" << endl;
00382 }
00383 
00384 template<typename FeatureType>
00385 void ICCVTutorial<FeatureType>::run()
00386 {
00387   visualizer_.spin ();
00388 }
00389 
00390 template<typename FeatureType>
00391 void ICCVTutorial<FeatureType>::keyboard_callback (const pcl::visualization::KeyboardEvent& event, void* cookie)
00392 {
00393   if (event.keyUp())
00394   {
00395     switch (event.getKeyCode())
00396     {
00397       case '1':
00398         if (!visualizer_.removePointCloud("source_points"))
00399         {
00400           visualizer_.addPointCloud(source_, "source_points");
00401         }
00402         break;
00403         
00404       case '2':
00405         if (!visualizer_.removePointCloud("target_points"))
00406         {
00407           visualizer_.addPointCloud(target_, "target_points");
00408         }
00409         break;
00410       
00411       case '3':
00412         if (!visualizer_.removePointCloud("source_segmented"))
00413         {
00414           visualizer_.addPointCloud(source_segmented_, "source_segmented");
00415         }
00416         break;
00417         
00418       case '4':
00419         if (!visualizer_.removePointCloud("target_segmented"))
00420         {
00421           visualizer_.addPointCloud(target_segmented_, "target_segmented");
00422         }
00423         break;
00424         
00425       case '5':
00426         if (!visualizer_.removePointCloud("source_keypoints"))
00427         {
00428           pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZI> keypoint_color (source_keypoints_, 0, 0, 255);
00429           //pcl::visualization::PointCloudColorHandlerGenericField<pcl::PointXYZI> keypoint_color (source_keypoints_, "intensity");
00430           visualizer_.addPointCloud(source_keypoints_, keypoint_color, "source_keypoints");
00431         }
00432         break;
00433       
00434       case '6':
00435         if (!visualizer_.removePointCloud("target_keypoints"))
00436         {
00437           //pcl::visualization::PointCloudColorHandlerGenericField<pcl::PointXYZI> keypoint_color (target_keypoints_, "intensity");
00438           pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZI> keypoint_color (target_keypoints_, 255, 0, 0);
00439           visualizer_.addPointCloud(target_keypoints_, keypoint_color, "target_keypoints");
00440         }
00441         break;
00442 
00443       case '7':
00444         if (!show_source2target_)
00445           visualizer_.addCorrespondences<pcl::PointXYZI>(source_keypoints_, target_keypoints_, source2target_, "source2target");
00446         else
00447           visualizer_.removeCorrespondences("source2target");
00448           
00449         show_source2target_ = !show_source2target_;
00450         break;
00451 
00452       case '8':
00453         if (!show_target2source_)
00454           visualizer_.addCorrespondences<pcl::PointXYZI>(target_keypoints_, source_keypoints_, target2source_, "target2source");
00455         else
00456           visualizer_.removeCorrespondences("target2source");
00457 
00458         show_target2source_ = !show_target2source_;
00459         break;
00460         
00461       case '9':
00462         if (!show_correspondences)
00463           visualizer_.addCorrespondences<pcl::PointXYZI>(source_keypoints_, target_keypoints_, *correspondences_, "correspondences");
00464         else
00465           visualizer_.removeCorrespondences("correspondences");
00466         show_correspondences = !show_correspondences;
00467         break;
00468         
00469       case 'i':
00470       case 'I':
00471         if (!visualizer_.removePointCloud("transformed"))
00472           visualizer_.addPointCloud(source_transformed_, "transformed");
00473         break;
00474 
00475       case 'r':
00476       case 'R':
00477         if (!visualizer_.removePointCloud("registered"))
00478           visualizer_.addPointCloud(source_registered_, "registered");
00479         break;
00480         
00481       case 't':
00482       case 'T':
00483           visualizer_.addPolygonMesh(surface_, "surface");
00484         break;
00485     }
00486   }
00487 }
00488 
00489 int 
00490 main (int argc, char ** argv)
00491 {
00492   if (argc < 6) 
00493   {
00494     pcl::console::print_info ("Syntax is: %s <source-pcd-file> <target-pcd-file> <keypoint-method> <descriptor-type> <surface-reconstruction-method>\n", argv[0]);
00495     pcl::console::print_info ("available <keypoint-methods>: 1 = Sift3D\n");
00496     pcl::console::print_info ("                              2 = Harris3D\n");
00497     pcl::console::print_info ("                              3 = Tomasi3D\n");
00498     pcl::console::print_info ("                              4 = Noble3D\n");
00499     pcl::console::print_info ("                              5 = Lowe3D\n");
00500     pcl::console::print_info ("                              6 = Curvature3D\n\n");
00501     pcl::console::print_info ("available <descriptor-types>: 1 = FPFH\n");
00502     pcl::console::print_info ("                              2 = SHOTRGB\n");
00503     pcl::console::print_info ("                              3 = PFH\n");
00504     pcl::console::print_info ("                              4 = PFHRGB\n\n");
00505     pcl::console::print_info ("available <surface-methods>:  1 = Greedy Projection\n");
00506     pcl::console::print_info ("                              2 = Marching Cubes\n");    
00507     
00508     return (1);
00509   }
00510   pcl::console::print_info ("== MENU ==\n");
00511   pcl::console::print_info ("1 - show/hide source point cloud\n");
00512   pcl::console::print_info ("2 - show/hide target point cloud\n");
00513   pcl::console::print_info ("3 - show/hide segmented source point cloud\n");
00514   pcl::console::print_info ("4 - show/hide segmented target point cloud\n");
00515   pcl::console::print_info ("5 - show/hide source key points\n");
00516   pcl::console::print_info ("6 - show/hide target key points\n");
00517   pcl::console::print_info ("7 - show/hide source2target correspondences\n");
00518   pcl::console::print_info ("8 - show/hide target2source correspondences\n");
00519   pcl::console::print_info ("9 - show/hide consistent correspondences\n");
00520   pcl::console::print_info ("i - show/hide initial alignment\n");
00521   pcl::console::print_info ("r - show/hide final registration\n");
00522   pcl::console::print_info ("t - show/hide triangulation (surface reconstruction)\n");
00523   pcl::console::print_info ("h - show visualizer options\n");
00524   pcl::console::print_info ("q - quit\n");
00525   
00526   pcl::PointCloud<pcl::PointXYZRGB>::Ptr source (new pcl::PointCloud<pcl::PointXYZRGB>);
00527   pcl::io::loadPCDFile (argv[1], *source);
00528   
00529   pcl::PointCloud<pcl::PointXYZRGB>::Ptr target (new pcl::PointCloud<pcl::PointXYZRGB>);
00530   pcl::io::loadPCDFile (argv[2], *target);
00531   
00532   int keypoint_type   = atoi (argv[3]);
00533   int descriptor_type = atoi (argv[4]);
00534   int surface_type    = atoi (argv[5]);
00535   
00536   boost::shared_ptr<pcl::Keypoint<pcl::PointXYZRGB, pcl::PointXYZI> > keypoint_detector;
00537   
00538   if (keypoint_type == 1)
00539   {
00540     pcl::SIFTKeypoint<pcl::PointXYZRGB, pcl::PointXYZI>* sift3D = new pcl::SIFTKeypoint<pcl::PointXYZRGB, pcl::PointXYZI>;
00541     sift3D->setScales(0.01, 3, 2);
00542     sift3D->setMinimumContrast(0.0);
00543     keypoint_detector.reset(sift3D);
00544   }
00545   else
00546   {
00547     pcl::HarrisKeypoint3D<pcl::PointXYZRGB,pcl::PointXYZI>* harris3D = new pcl::HarrisKeypoint3D<pcl::PointXYZRGB,pcl::PointXYZI> (pcl::HarrisKeypoint3D<pcl::PointXYZRGB,pcl::PointXYZI>::HARRIS);
00548     harris3D->setNonMaxSupression(true);
00549     harris3D->setRadius (0.01);
00550     harris3D->setRadiusSearch (0.01);
00551     keypoint_detector.reset(harris3D);
00552     switch (keypoint_type)
00553     {
00554       case 2:
00555         harris3D->setMethod(pcl::HarrisKeypoint3D<pcl::PointXYZRGB,pcl::PointXYZI>::HARRIS);
00556       break;
00557 
00558       case 3:
00559         harris3D->setMethod(pcl::HarrisKeypoint3D<pcl::PointXYZRGB,pcl::PointXYZI>::TOMASI);
00560       break;
00561 
00562       case 4:
00563         harris3D->setMethod(pcl::HarrisKeypoint3D<pcl::PointXYZRGB,pcl::PointXYZI>::NOBLE);
00564       break;
00565       
00566       case 5:
00567         harris3D->setMethod(pcl::HarrisKeypoint3D<pcl::PointXYZRGB,pcl::PointXYZI>::LOWE);
00568       break;
00569 
00570       case 6:
00571         harris3D->setMethod(pcl::HarrisKeypoint3D<pcl::PointXYZRGB,pcl::PointXYZI>::CURVATURE);
00572       break;
00573       default:
00574         pcl::console::print_error("unknown key point detection method %d\n expecting values between 1 and 6", keypoint_type);
00575         exit (1);
00576         break;
00577     }
00578     
00579   }
00580   
00581   boost::shared_ptr<pcl::PCLSurfaceBase<pcl::PointXYZRGBNormal> > surface_reconstruction;
00582   
00583   if (surface_type == 1)
00584   {
00585     pcl::GreedyProjectionTriangulation<pcl::PointXYZRGBNormal>* gp3 = new pcl::GreedyProjectionTriangulation<pcl::PointXYZRGBNormal>;
00586 
00587     // Set the maximum distance between connected points (maximum edge length)
00588     gp3->setSearchRadius (0.025);
00589 
00590     // Set typical values for the parameters
00591     gp3->setMu (2.5);
00592     gp3->setMaximumNearestNeighbors (100);
00593     gp3->setMaximumSurfaceAngle(M_PI/4); // 45 degrees
00594     gp3->setMinimumAngle(M_PI/18); // 10 degrees
00595     gp3->setMaximumAngle(2*M_PI/3); // 120 degrees
00596     gp3->setNormalConsistency(false);
00597     surface_reconstruction.reset(gp3);
00598   }
00599   else if (surface_type == 2)
00600   {
00601     pcl::MarchingCubes<pcl::PointXYZRGBNormal>* mc = new pcl::MarchingCubesHoppe<pcl::PointXYZRGBNormal>;
00602     mc->setIsoLevel(0.001);
00603     mc->setGridResolution(50, 50, 50);
00604     surface_reconstruction.reset(mc);
00605   }
00606   else
00607   {
00608     pcl::console::print_error("unknown surface reconstruction method %d\n expecting values between 1 and 2", surface_type);
00609     exit (1);
00610   }
00611   
00612   switch (descriptor_type)
00613   {
00614     case 1:
00615     {
00616       pcl::Feature<pcl::PointXYZRGB, pcl::FPFHSignature33>::Ptr feature_extractor (new pcl::FPFHEstimationOMP<pcl::PointXYZRGB, pcl::Normal, pcl::FPFHSignature33>); 
00617       feature_extractor->setSearchMethod (pcl::search::Search<pcl::PointXYZRGB>::Ptr (new pcl::search::KdTree<pcl::PointXYZRGB>));
00618       feature_extractor->setRadiusSearch (0.05);
00619       ICCVTutorial<pcl::FPFHSignature33> tutorial (keypoint_detector, feature_extractor, surface_reconstruction, source, target);
00620       tutorial.run ();
00621     }
00622     break;
00623     
00624     case 2:
00625     {
00626       pcl::SHOTEstimationOMP<pcl::PointXYZRGB, pcl::Normal, pcl::SHOT>* shot = new pcl::SHOTEstimationOMP<pcl::PointXYZRGB, pcl::Normal, pcl::SHOT>;
00627       shot->setRadiusSearch (0.04);
00628       pcl::Feature<pcl::PointXYZRGB, pcl::SHOT>::Ptr feature_extractor (shot);
00629       ICCVTutorial<pcl::SHOT> tutorial (keypoint_detector, feature_extractor, surface_reconstruction, source, target);
00630       tutorial.run ();
00631     }
00632     break;
00633     
00634     case 3:
00635     {
00636       pcl::Feature<pcl::PointXYZRGB, pcl::PFHSignature125>::Ptr feature_extractor (new pcl::PFHEstimation<pcl::PointXYZRGB, pcl::Normal, pcl::PFHSignature125>);
00637       feature_extractor->setKSearch(50);
00638       ICCVTutorial<pcl::PFHSignature125> tutorial (keypoint_detector, feature_extractor, surface_reconstruction, source, target);
00639       tutorial.run ();
00640     }
00641     break;
00642     
00643     case 4:
00644     {
00645       pcl::Feature<pcl::PointXYZRGB, pcl::PFHRGBSignature250>::Ptr feature_extractor (new pcl::PFHRGBEstimation<pcl::PointXYZRGB, pcl::Normal, pcl::PFHRGBSignature250>);
00646       feature_extractor->setKSearch(50);
00647       ICCVTutorial<pcl::PFHRGBSignature250> tutorial (keypoint_detector, feature_extractor, surface_reconstruction, source, target);
00648       tutorial.run ();
00649     }
00650     break;
00651     
00652     default:
00653       pcl::console::print_error("unknown descriptor type %d\n expecting values between 1 and 4", descriptor_type);
00654       exit (1);
00655       break;
00656   }  
00657   
00658   return (0);
00659 }


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:18:55