eval_clustering.cpp
Go to the documentation of this file.
00001 /*
00002  * classify_new.cpp
00003  *
00004  *  Created on: Jun 11, 2012
00005  *      Author: vsu
00006  */
00007 
00008 /*
00009  * classify.cpp
00010  *
00011  *  Created on: Apr 25, 2012
00012  *      Author: vsu
00013  */
00014 
00015 #include <pcl17/console/parse.h>
00016 #include <pcl17/console/print.h>
00017 #include <pcl17/sample_consensus/ransac.h>
00018 #include <pcl17/filters/passthrough.h>
00019 #include <pcl17/octree/octree.h>
00020 #include <pcl17/classification/PHVObjectClassifier.h>
00021 #include <pcl17/features/sgfall.h>
00022 #include <sac_3dof.h>
00023 #include <set>
00024 #include <pcl17/io/pcd_io.h>
00025 #include <ransac_simple.h>
00026 #include <pcl17/features/vfh.h>
00027 
00028 template<class FeatureType, class FeatureEstimatorType>
00029   void eval_clustering(string database_dir, string scans_dir,const  std::string & extermal_classifier_file)
00030   {
00031     std::string debug_folder = "eval_debug/";
00032 
00033     for (float lmt = 0.0f; lmt <= 1.0f; lmt += 0.1f)
00034     {
00035 
00036       pcl17::PHVObjectClassifier<pcl17::PointXYZ, pcl17::PointNormal, FeatureType> oc;
00037 
00038       typename pcl17::Feature<pcl17::PointNormal, FeatureType>::Ptr feature_estimator(new FeatureEstimatorType);
00039       oc.setFeatureEstimator(feature_estimator);
00040 
00041       oc.setDatabaseDir(database_dir);
00042       oc.loadFromFile();
00043 
00044       oc.setDebugFolder(debug_folder);
00045       oc.setDebug(false);
00046 
00047       pcl17::PointCloud<pcl17::PointXYZ>::Ptr cloud(new pcl17::PointCloud<pcl17::PointXYZ>);
00048 
00049       //int iter = 0;
00050 
00051       oc.setLocalMaximaThreshold(lmt);
00052 
00053       double tp = 0, fn = 0, fp = 0;
00054 
00055       boost::filesystem::directory_iterator dir_iter(scans_dir), end;
00056 
00057       BOOST_FOREACH(const boost::filesystem::path& class_dir, std::make_pair(dir_iter, end))
00058 {      boost::filesystem::directory_iterator class_dir_iter(class_dir), end;
00059       BOOST_FOREACH(const boost::filesystem::path& model_dir, std::make_pair(class_dir_iter, end))
00060       {
00061 
00062         boost::filesystem::directory_iterator model_dir_iter(model_dir), end;
00063         BOOST_FOREACH(const boost::filesystem::path& v, std::make_pair(model_dir_iter, end))
00064         {
00065           if((v.extension() == ".pcd") && (v.filename() != "full.pcd"))
00066           {
00067             //std::cerr << "Processing scan number " << iter << std::endl;
00068             //iter++;
00069             pcl17::io::loadPCDFile(v.c_str(), *cloud);
00070             oc.setScene(cloud, 2.4);
00071 
00072             if(extermal_classifier_file == "")
00073             {
00074               oc.eval_clustering(class_dir.filename().string(), 0.02f, tp, fn, fp);
00075             }
00076             else
00077             {
00078               oc.eval_clustering_external(class_dir.filename().string(), 0.02f, tp, fn, fp, extermal_classifier_file);
00079             }
00080 
00081             //oc.addObjectPartialView(cloud, class_dir.filename().c_str());
00082           }
00083 
00084         }
00085 
00086       }
00087 
00088     }
00089 
00090     //    std::cout << "True Positive: " << tp << std::endl;
00091     //    std::cout << "False Positive: " << fp << std::endl;
00092     //    std::cout << "False Negative: " << fn << std::endl;
00093     //    std::cout << "Precision: " << tp/(tp+fp) << std::endl;
00094     //    std::cout << "Recall: " << tp/(tp+fn) << std::endl;
00095 
00096     std::cout << lmt << " " << tp << " " << fp << " " << fn << " " << tp/(tp+fp) << " " << tp/(tp+fn) << std::endl;
00097 
00098   }
00099 }
00100 
00101 int main(int argc, char** argv)
00102 {
00103 
00104   if (argc < 5)
00105   {
00106     PCL17_INFO ("Usage %s -scans_dir /dir/with/scans -database_dir /where/to/put/database [options]\n", argv[0]);
00107     return -1;
00108   }
00109 
00110   std::string database_dir;
00111   std::string scans_dir;
00112   std::string features = "sgf";
00113   std::string extermal_classifier_file = "";
00114 
00115   pcl17::console::parse_argument(argc, argv, "-database_dir", database_dir);
00116   pcl17::console::parse_argument(argc, argv, "-scans_dir", scans_dir);
00117   pcl17::console::parse_argument(argc, argv, "-features", features);
00118   pcl17::console::parse_argument(argc, argv, "-extermal_classifier_file", extermal_classifier_file);
00119 
00120   if (features == "sgf")
00121   {
00122     eval_clustering<pcl17::Histogram<pcl17::SGFALL_SIZE>, pcl17::SGFALLEstimation<pcl17::PointNormal, pcl17::Histogram<
00123         pcl17::SGFALL_SIZE> > > (database_dir, scans_dir, extermal_classifier_file
00124 
00125     );
00126   }
00127   else if (features == "esf")
00128   {
00129     eval_clustering<pcl17::ESFSignature640, pcl17::ESFEstimation<pcl17::PointNormal, pcl17::ESFSignature640> > (database_dir,
00130                                                                                                         scans_dir,
00131                                                                                                         extermal_classifier_file);
00132   }
00133   else if (features == "vfh")
00134   {
00135     eval_clustering<pcl17::VFHSignature308, pcl17::VFHEstimation<pcl17::PointNormal, pcl17::PointNormal, pcl17::VFHSignature308> > (
00136                                                                                                                           database_dir,
00137                                                                                                                           scans_dir,
00138                                                                                                                           extermal_classifier_file);
00139   }
00140   else
00141   {
00142     std::cerr << "Unknown feature type " << features << " specified" << std::endl;
00143   }
00144 
00145   return 0;
00146 }
00147 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


furniture_classification
Author(s): Vladyslav Usenko
autogenerated on Sun Oct 6 2013 12:12:30