build_tree.cpp
Go to the documentation of this file.
00001 #include <pcl/point_types.h>
00002 #include <pcl/point_cloud.h>
00003 #include <pcl/console/parse.h>
00004 #include <pcl/console/print.h>
00005 #include <pcl/io/pcd_io.h>
00006 #include <boost/filesystem.hpp>
00007 #include <flann/flann.h>
00008 #include <flann/io/hdf5.h>
00009 #include <fstream>
00010 
00011 typedef std::pair<std::string, std::vector<float> > vfh_model;
00012 
00017 bool
00018 loadHist (const boost::filesystem::path &path, vfh_model &vfh)
00019 {
00020   int vfh_idx;
00021   // Load the file as a PCD
00022   try
00023   {
00024     pcl::PCLPointCloud2 cloud;
00025     int version;
00026     Eigen::Vector4f origin;
00027     Eigen::Quaternionf orientation;
00028     pcl::PCDReader r;
00029     int type; unsigned int idx;
00030     r.readHeader (path.string (), cloud, origin, orientation, version, type, idx);
00031 
00032     vfh_idx = pcl::getFieldIndex (cloud, "vfh");
00033     if (vfh_idx == -1)
00034       return (false);
00035     if ((int)cloud.width * cloud.height != 1)
00036       return (false);
00037   }
00038   catch (pcl::InvalidConversionException e)
00039   {
00040     return (false);
00041   }
00042 
00043   // Treat the VFH signature as a single Point Cloud
00044   pcl::PointCloud <pcl::VFHSignature308> point;
00045   pcl::io::loadPCDFile (path.string (), point);
00046   vfh.second.resize (308);
00047 
00048   std::vector <pcl::PCLPointField> fields;
00049   pcl::getFieldIndex (point, "vfh", fields);
00050 
00051   for (size_t i = 0; i < fields[vfh_idx].count; ++i)
00052   {
00053     vfh.second[i] = point.points[0].histogram[i];
00054   }
00055   vfh.first = path.string ();
00056   return (true);
00057 }
00058 
00065 void
00066 loadFeatureModels (const boost::filesystem::path &base_dir, const std::string &extension, 
00067                    std::vector<vfh_model> &models)
00068 {
00069   if (!boost::filesystem::exists (base_dir) && !boost::filesystem::is_directory (base_dir))
00070     return;
00071 
00072   for (boost::filesystem::directory_iterator it (base_dir); it != boost::filesystem::directory_iterator (); ++it)
00073   {
00074     if (boost::filesystem::is_directory (it->status ()))
00075     {
00076       std::stringstream ss;
00077       ss << it->path ();
00078       pcl::console::print_highlight ("Loading %s (%lu models loaded so far).\n", ss.str ().c_str (), (unsigned long)models.size ());
00079       loadFeatureModels (it->path (), extension, models);
00080     }
00081     if (boost::filesystem::is_regular_file (it->status ()) && boost::filesystem::extension (it->path ()) == extension)
00082     {
00083       vfh_model m;
00084       if (loadHist (base_dir / it->path ().filename (), m))
00085         models.push_back (m);
00086     }
00087   }
00088 }
00089 
00090 int
00091 main (int argc, char** argv)
00092 {
00093   if (argc < 2)
00094   {
00095     PCL_ERROR ("Need at least two parameters! Syntax is: %s [model_directory] [options]\n", argv[0]);
00096     return (-1);
00097   }
00098 
00099   std::string extension (".pcd");
00100   transform (extension.begin (), extension.end (), extension.begin (), (int(*)(int))tolower);
00101 
00102   std::string kdtree_idx_file_name = "kdtree.idx";
00103   std::string training_data_h5_file_name = "training_data.h5";
00104   std::string training_data_list_file_name = "training_data.list";
00105 
00106   std::vector<vfh_model> models;
00107 
00108   // Load the model histograms
00109   loadFeatureModels (argv[1], extension, models);
00110   pcl::console::print_highlight ("Loaded %d VFH models. Creating training data %s/%s.\n", 
00111       (int)models.size (), training_data_h5_file_name.c_str (), training_data_list_file_name.c_str ());
00112 
00113   // Convert data into FLANN format
00114   flann::Matrix<float> data (new float[models.size () * models[0].second.size ()], models.size (), models[0].second.size ());
00115 
00116   for (size_t i = 0; i < data.rows; ++i)
00117     for (size_t j = 0; j < data.cols; ++j)
00118       data[i][j] = models[i].second[j];
00119 
00120   // Save data to disk (list of models)
00121   flann::save_to_file (data, training_data_h5_file_name, "training_data");
00122   std::ofstream fs;
00123   fs.open (training_data_list_file_name.c_str ());
00124   for (size_t i = 0; i < models.size (); ++i)
00125     fs << models[i].first << "\n";
00126   fs.close ();
00127  
00128   // Build the tree index and save it to disk
00129   pcl::console::print_error ("Building the kdtree index (%s) for %d elements...\n", kdtree_idx_file_name.c_str (), (int)data.rows);
00130   flann::Index<flann::ChiSquareDistance<float> > index (data, flann::LinearIndexParams ());
00131   //flann::Index<flann::ChiSquareDistance<float> > index (data, flann::KDTreeIndexParams (4));
00132   index.buildIndex ();
00133   index.save (kdtree_idx_file_name);
00134   delete[] data.ptr ();
00135 
00136   return (0);
00137 }


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