Go to the documentation of this file.00001
00067 #include <boost/program_options.hpp>
00068 #include <fstream>
00069
00070 #include <pcl/point_types.h>
00071 #include <pcl/io/pcd_io.h>
00072 #include <pcl/common/file_io.h>
00073
00074 #include <cob_3d_mapping_common/label_defines.h>
00075
00076 using namespace std;
00077 using namespace pcl;
00078
00079 string outfolder_;
00080 vector<string> folder_in_;
00081
00082 void readOptions(int argc, char* argv[])
00083 {
00084 using namespace boost::program_options;
00085
00086 options_description cmd_line("Options");
00087 cmd_line.add_options()
00088 ("help", "produce help messsage")
00089 ("out,o", value<string>(&outfolder_), "output folder")
00090 ("in,i", value<vector<string> >(&folder_in_), "in files")
00091 ;
00092
00093 positional_options_description p_opt;
00094 p_opt.add("in", -1);
00095
00096 variables_map vm;
00097 store(command_line_parser(argc, argv)
00098 .options(cmd_line)
00099 .positional(p_opt).run(), vm);
00100 notify(vm);
00101
00102 if (vm.count("help") || !vm.count("in"))
00103 {
00104 cout << "script merges fpfh PCD file from multiple source files into single one "
00105 << "and generates a label reference file for the knn classifier." << endl;
00106 cout << "Searches for files containing the strings:" << endl;
00107 cout << "\t \"plane\"" << endl;
00108 cout << "\t \"edge_convex_\"" << endl;
00109 cout << "\t \"edge_concave_\"" << endl;
00110 cout << "\t \"sphere_convex_\"" << endl;
00111 cout << "\t \"sphere_concave_\"" << endl;
00112 cout << "\t \"cylinder_convex_\"" << endl;
00113 cout << "\t \"cylinder_concave_\"" << endl;
00114 cout << cmd_line << endl;
00115 exit(0);
00116 }
00117 }
00118
00119 int main(int argc, char** argv)
00120 {
00121 readOptions(argc, argv);
00122
00123 PointCloud<FPFHSignature33> plane, e_vex, e_cav, c_vex, c_cav, s_vex, s_cav, tmp, all;
00124 PCDReader r;
00125 for (size_t j = 0; j < folder_in_.size(); j++)
00126 {
00127 vector<string> files;
00128 getAllPcdFilesInDirectory(folder_in_[j], files);
00129 for (size_t i = 0; i < files.size(); i++)
00130 {
00131 files[i] = folder_in_[j] + files[i];
00132 r.read(files[i], tmp);
00133 if(string::npos != files[i].rfind("plane"))
00134 plane += tmp;
00135 else if (string::npos != files[i].rfind("edge_convex_"))
00136 e_vex += tmp;
00137 else if (string::npos != files[i].rfind("edge_concave_"))
00138 e_cav += tmp;
00139 else if (string::npos != files[i].rfind("sphere_convex_"))
00140 s_vex += tmp;
00141 else if (string::npos != files[i].rfind("sphere_concave_"))
00142 s_cav += tmp;
00143 else if (string::npos != files[i].rfind("cylinder_convex_"))
00144 c_vex += tmp;
00145 else if (string::npos != files[i].rfind("cylinder_concave_"))
00146 c_cav += tmp;
00147 tmp.clear();
00148 }
00149 }
00150
00151 all += plane;
00152 all += e_vex;
00153 all += e_cav;
00154 all += c_vex;
00155 all += c_cav;
00156 all += s_vex;
00157 all += s_cav;
00158 PCDWriter w;
00159 w.write(outfolder_ + "knn_fpfh_features.pcd", all);
00160
00161 string labels_file_name;
00162 labels_file_name = outfolder_ + "knn_labels.txt";
00163 ofstream f (labels_file_name.c_str());
00164 f << "CS" << endl;
00165 for(size_t i = 0; i < plane.size(); ++i)
00166 f << SVM_PLANE << endl;
00167 for(size_t i = 0; i < e_vex.size(); ++i)
00168 f << SVM_EDGE_CVX << endl;
00169 for(size_t i = 0; i < e_cav.size(); ++i)
00170 f << SVM_EDGE_CAV << endl;
00171 for(size_t i = 0; i < c_vex.size(); ++i)
00172 f << SVM_CYL_CVX << endl;
00173 for(size_t i = 0; i < c_cav.size(); ++i)
00174 f << SVM_CYL_CAV << endl;
00175 for(size_t i = 0; i < s_vex.size(); ++i)
00176 f << SVM_SPH_CVX << endl;
00177 for(size_t i = 0; i < s_cav.size(); ++i)
00178 f << SVM_SPH_CAV << endl;
00179 f.close();
00180
00181 return 1;
00182
00183 }