train.cpp
Go to the documentation of this file.
00001 /*
00002  * region_grow.cpp
00003  *
00004  *  Created on: May 30, 2012
00005  *      Author: vsu
00006  */
00007 
00008 #include <pcl17/console/print.h>
00009 #include <pcl17/point_types.h>
00010 #include <pcl17/features/sgfall.h>
00011 #include <pcl17/console/parse.h>
00012 #include <pcl17/classification/PHVObjectClassifier.h>
00013 #include <pcl17/features/vfh.h>
00014 
00015 template<class FeatureType, class FeatureEstimatorType>
00016   void train(string input_dir, string output_dir, int num_clusters, const std::string & extermal_classifier_file)
00017   {
00018     pcl17::PHVObjectClassifier<pcl17::PointXYZ, pcl17::PointNormal, FeatureType> oc;
00019     oc.setDebugFolder("debug/");
00020     //oc.setDebug(true);
00021 
00022     typename pcl17::Feature<pcl17::PointNormal, FeatureType>::Ptr feature_estimator(new FeatureEstimatorType);
00023     oc.setFeatureEstimator(feature_estimator);
00024 
00025     //PCL_INFO("Processing following files:\n");
00026 
00027     pcl17::PointCloud<pcl17::PointXYZ>::Ptr cloud(new pcl17::PointCloud<pcl17::PointXYZ>);
00028 
00029     boost::filesystem::directory_iterator dir_iter(input_dir), end;
00030 
00031     BOOST_FOREACH(const boost::filesystem::path& class_dir, std::make_pair(dir_iter, end))
00032 {    boost::filesystem::directory_iterator class_dir_iter(class_dir), end;
00033     BOOST_FOREACH(const boost::filesystem::path& model_dir, std::make_pair(class_dir_iter, end))
00034     {
00035 
00036       boost::filesystem::directory_iterator model_dir_iter(model_dir), end;
00037       BOOST_FOREACH(const boost::filesystem::path& v, std::make_pair(model_dir_iter, end))
00038       {
00039         if(v.filename() == "full.pcd")
00040         {
00041 
00042           pcl17::io::loadPCDFile(v.c_str(), *cloud);
00043           oc.addObjectFullModel(cloud, class_dir.filename().c_str());
00044         }
00045 
00046         if(v.extension() == ".pcd")
00047         {
00048           pcl17::io::loadPCDFile(v.c_str(), *cloud);
00049           oc.addObjectPartialView(cloud, class_dir.filename().c_str());
00050         }
00051 
00052       }
00053 
00054     }
00055 
00056   }
00057   oc.setNumberOfClusters(num_clusters);
00058   if (extermal_classifier_file != "")
00059   {
00060     oc.computeExternalClassifier(extermal_classifier_file);
00061   }
00062   else
00063   {
00064     oc.computeClassifier();
00065   }
00066   oc.setDatabaseDir(output_dir);
00067   oc.saveToFile();
00068 }
00069 
00070 int main(int argc, char **argv)
00071 {
00072 
00073   if (argc < 5)
00074   {
00075     PCL17_INFO ("Usage %s -input_dir /dir/with/pointclouds -output_dir /where/to/put/database [options]\n", argv[0]);
00076     PCL17_INFO (" * where options are:\n"
00077         "         -min_points_in_segment <X>  : set minimal number of points in segment to X. Default : 300\n"
00078         "         -num_clusters <X>           : set Number of clusters. Default : 5\n"
00079         "         -features <X>               : which features to use (sgf, vfh, esf). Default : sgf\n"
00080         "");
00081     return -1;
00082   }
00083 
00084   std::string input_dir;
00085   std::string output_dir;
00086   int num_clusters = 40;
00087   std::string features = "sgf";
00088   std::string extermal_classifier_file = "";
00089 
00090   pcl17::console::parse_argument(argc, argv, "-input_dir", input_dir);
00091   pcl17::console::parse_argument(argc, argv, "-output_dir", output_dir);
00092   pcl17::console::parse_argument(argc, argv, "-num_clusters", num_clusters);
00093   pcl17::console::parse_argument(argc, argv, "-features", features);
00094   pcl17::console::parse_argument(argc, argv, "-extermal_classifier_file", extermal_classifier_file);
00095 
00096   if (features == "sgf")
00097   {
00098     train<pcl17::Histogram<pcl17::SGFALL_SIZE>, pcl17::SGFALLEstimation<pcl17::PointNormal, pcl17::Histogram<pcl17::SGFALL_SIZE> > > (
00099                                                                                                                           input_dir,
00100                                                                                                                           output_dir,
00101                                                                                                                           num_clusters,
00102                                                                                                                           extermal_classifier_file);
00103   }
00104   else if (features == "esf")
00105   {
00106     train<pcl17::ESFSignature640, pcl17::ESFEstimation<pcl17::PointNormal, pcl17::ESFSignature640> > (input_dir, output_dir,
00107                                                                                               num_clusters,
00108                                                                                               extermal_classifier_file);
00109   }
00110   else if (features == "vfh")
00111   {
00112     train<pcl17::VFHSignature308, pcl17::VFHEstimation<pcl17::PointNormal, pcl17::PointNormal, pcl17::VFHSignature308> > (
00113                                                                                                                 input_dir,
00114                                                                                                                 output_dir,
00115                                                                                                                 num_clusters,
00116                                                                                                                 extermal_classifier_file);
00117   }
00118   else
00119   {
00120     std::cerr << "Unknown feature type " << features << " specified" << std::endl;
00121   }
00122 
00123   return 0;
00124 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


furniture_classification
Author(s): Vladyslav Usenko
autogenerated on Thu May 23 2013 18:32:29