PHVObjectClassifier.h
Go to the documentation of this file.
00001 /*
00002  * PHVObjectClassifier.h
00003  *
00004  *  Created on: Jun 7, 2012
00005  *      Author: vsu
00006  */
00007 
00008 #ifndef PHVOBJECTCLASSIFIER_H_
00009 #define PHVOBJECTCLASSIFIER_H_
00010 
00011 #include <pcl17/point_types.h>
00012 #include <pcl17/features/feature.h>
00013 #include <pcl17/search/flann_search.h>
00014 #include <pcl17/search/impl/flann_search.hpp>
00015 #include <pcl17/kdtree/kdtree_flann.h>
00016 #include <pcl17/kdtree/impl/kdtree_flann.hpp>
00017 #include <pcl17/surface/mls.h>
00018 #include <pcl17/io/pcd_io.h>
00019 #include <pcl17/filters/voxel_grid.h>
00020 #include <pcl17/segmentation/region_growing.h>
00021 #include <pcl17/common/transforms.h>
00022 
00023 #include <pcl17/ModelCoefficients.h>
00024 #include <pcl17/io/pcd_io.h>
00025 #include <pcl17/point_types.h>
00026 #include <pcl17/sample_consensus/method_types.h>
00027 #include <pcl17/sample_consensus/model_types.h>
00028 #include <pcl17/segmentation/sac_segmentation.h>
00029 #include <pcl17/features/feature.h>
00030 #include <pcl17/registration/icp.h>
00031 #include <pcl17/registration/transformation_estimation_point_to_plane.h>
00032 
00033 #include <ransac_simple.h>
00034 #include <sac_3dof.h>
00035 
00036 #include <boost/foreach.hpp>
00037 #include <boost/filesystem.hpp>
00038 
00039 #include <yaml-cpp/yaml.h>
00040 
00041 #include <map>
00042 #include <set>
00043 #include <furniture_classification/Hypothesis.h>
00044 #include <furniture_classification/FittedModels.h>
00045 
00046 using std::map;
00047 using std::string;
00048 using std::vector;
00049 using std::set;
00050 
00051 namespace pcl17 {
00052 
00053 template<class PointT, class PointNormalT, class FeatureT>
00054 class PHVObjectClassifier {
00055 public:
00056 
00057         typedef typename pcl17::PointCloud<PointT> PointCloud;
00058         typedef typename pcl17::PointCloud<PointT>::Ptr PointCloudPtr;
00059         typedef typename pcl17::PointCloud<PointT>::ConstPtr PointCloudConstPtr;
00060 
00061         typedef typename pcl17::search::KdTree<PointT> PointTree;
00062         typedef typename pcl17::search::KdTree<PointT>::Ptr PointTreePtr;
00063 
00064         typedef typename pcl17::search::KdTree<PointNormalT> PointNormalTree;
00065         typedef typename pcl17::search::KdTree<PointNormalT>::Ptr PointNormalTreePtr;
00066 
00067         typedef typename pcl17::PointCloud<PointNormalT> PointNormalCloud;
00068         typedef typename pcl17::PointCloud<PointNormalT>::Ptr PointNormalCloudPtr;
00069         typedef typename pcl17::PointCloud<PointNormalT>::ConstPtr PointNormalCloudConstPtr;
00070 
00071         typedef typename Feature<PointNormalT, FeatureT>::Ptr FeatureEstimatorType;
00072         typedef typename boost::shared_ptr<MovingLeastSquares<PointT, PointNormalT> > MovingLeastSquaresType;
00073 
00074         typedef map<FeatureT, map<string, PointCloud> > DatabaseType;
00075         typedef map<string, vector<PointNormalCloudPtr> > ModelMapType;
00076         typedef typename ModelMapType::value_type ModelMapValueType;
00077 
00078         PHVObjectClassifier() :
00079                         subsampling_resolution_(0.02f), mls_polynomial_fit_(false), mls_polynomial_order_(
00080                                         2), mls_search_radius_(0.05f), min_points_in_segment_(100), rg_residual_threshold_(
00081                                         0.05f), rg_smoothness_threshold_(40 * M_PI / 180), fe_k_neighbours_(
00082                                         10), num_clusters_(40), num_neighbours_(1), cell_size_(
00083                                         0.01), local_maxima_threshold_(0.5f), window_size_(0.3), ransac_distance_threshold_(
00084                                         0.01f), ransac_vis_score_weight_(5), ransac_num_iter_(200), icp_treshold_(
00085                                         0.03), num_angles_(36), icp_max_iterations_(20), icp_max_correspondence_distance_(
00086                                         0.01), debug_(false), debug_folder_(""), mls_(
00087                                         new MovingLeastSquares<PointT, PointNormalT>) {
00088 
00089                 typedef pcl17::PointCloud<FeatureT> PointFeatureCloud;
00090                 database_features_cloud_.reset(new PointFeatureCloud);
00091                 ransac_result_threshold_["Armchairs"] = 0.01;
00092                 ransac_result_threshold_["Chairs"] = 0.03;
00093                 ransac_result_threshold_["Sideboards"] = 0.01;
00094                 ransac_result_threshold_["Tables"] = 0.1;
00095 
00096         }
00097         virtual ~PHVObjectClassifier() {
00098         }
00099         ;
00100 
00101         virtual void addObjectPartialView(PointCloudConstPtr view,
00102                         const std::string & class_name) {
00103                 class_name_to_partial_views_map_[class_name].push_back(
00104                                 estimateNormalsAndSubsample(view));
00105 
00106         }
00107         virtual void addObjectFullModel(PointCloudConstPtr model,
00108                         const std::string & class_name) {
00109                 class_name_to_full_models_map_[class_name].push_back(
00110                                 estimateNormalsAndSubsample(model));
00111         }
00112 
00113         virtual void computeClassifier();
00114         void computeExternalClassifier(const std::string & labels);
00115 
00116         virtual bool isClassifierComputed() {
00117                 return !this->database_.empty();
00118         }
00119 
00120         void saveToFile();
00121 
00122         void loadFromFile();
00123 
00124         void setDebug(bool debug) {
00125                 debug_ = debug;
00126         }
00127 
00128         bool getDebug() {
00129                 return debug_;
00130         }
00131 
00132         void setDebugFolder(const string & debug_folder) {
00133                 boost::filesystem::path debug_path(debug_folder);
00134                 debug_folder_ = boost::filesystem::system_complete(debug_path).c_str();
00135 
00136                 if (boost::filesystem::exists(debug_path)) {
00137                         boost::filesystem::remove_all(debug_path);
00138                 }
00139 
00140                 boost::filesystem::create_directories(debug_path);
00141 
00142         }
00143 
00144         string getDebugFolder() {
00145                 return debug_folder_;
00146         }
00147 
00148         void setNumberOfClusters(int num_clusters) {
00149                 num_clusters_ = num_clusters;
00150         }
00151 
00152         int getNumberOfClusters() {
00153                 return num_clusters_;
00154         }
00155 
00156         void setFeatureEstimator(FeatureEstimatorType feature_estimator) {
00157                 feature_estimator_ = feature_estimator;
00158         }
00159 
00160         FeatureEstimatorType getFeatureEstimator() {
00161                 return feature_estimator_;
00162         }
00163 
00164         void setLocalMaximaThreshold(float t) {
00165                 local_maxima_threshold_ = t;
00166         }
00167 
00168         float getLocalMaximaThreshold() {
00169                 return local_maxima_threshold_;
00170         }
00171 
00172         virtual void setScene(PointCloudConstPtr model, float cut_off_distance =
00173                         2.5f) {
00174                 std::vector<int> idx;
00175 
00176                 pcl17::PassThrough<PointT> pass;
00177                 pass.setInputCloud(model);
00178                 pass.setFilterFieldName("x");
00179                 pass.setFilterLimits(-cut_off_distance, cut_off_distance);
00180                 pass.filter(idx);
00181 
00182                 PointCloudPtr model_cut(new PointCloud(*model, idx));
00183 
00184                 scene_ = estimateNormalsAndSubsample(model_cut);
00185                 pcl17::getMinMax3D<PointNormalT>(*scene_, min_scene_bound_,
00186                                 max_scene_bound_);
00187         }
00188 
00189         PointNormalCloudPtr getScene() {
00190                 return scene_;
00191         }
00192 
00193         void classify();
00194 
00195         void setDatabaseDir(const string & database_dir) {
00196                 database_dir_ = database_dir;
00197         }
00198 
00199         string getDatabaseDir() {
00200                 return database_dir_;
00201         }
00202 
00203         map<string, vector<PointNormalCloudPtr> > getFoundObjects() {
00204                 return found_objects_;
00205         }
00206 
00207         void eval_clustering(const std::string & classname,
00208                         const float search_radius, double &tp, double &fn, double &fp);
00209 
00210         template<class PT, class PNT, class FT>
00211         friend YAML::Emitter& operator <<(YAML::Emitter& out,
00212                         const PHVObjectClassifier<PT, PNT, FT> & h);
00213 
00214         void eval_clustering_external(const std::string & classname,
00215                         const float search_radius, double &tp, double &fn, double &fp,
00216                         const std::string & matrix);
00217 
00218         void vote_external(const std::string & matrix);
00219         furniture_classification::Hypothesis::Ptr generate_hypothesis(
00220                         std::map<std::string, pcl17::PointCloud<pcl17::PointXYZ>::Ptr> & votes_map);
00221         furniture_classification::FittedModelsPtr fit_objects(
00222                         furniture_classification::Hypothesis::ConstPtr hp);
00223 
00224 protected:
00225 
00226         typename pcl17::PointCloud<PointNormalT>::Ptr
00227         estimateNormalsAndSubsample(
00228                         typename pcl17::PointCloud<PointT>::ConstPtr cloud_orig);
00229         void getSegmentsFromCloud(PointNormalCloudPtr cloud_with_normals,
00230                         vector<boost::shared_ptr<vector<int> > > & segment_indices,
00231                         pcl17::PointCloud<pcl17::PointXYZRGBNormal>::Ptr & colored_segments);
00232         void appendFeaturesFromCloud(PointNormalCloudPtr & cloud,
00233                         const string & class_name, const int i);
00234         void normalizeFeatures(std::vector<FeatureT> & features);
00235         void normalizeFeaturesWithCurrentMinMax(std::vector<FeatureT> & features);
00236         void clusterFeatures(vector<FeatureT> & cluster_centers,
00237                         vector<int> & cluster_labels);
00238         void vote();
00239         Eigen::MatrixXf projectVotesToGrid(
00240                         const pcl17::PointCloud<pcl17::PointXYZI> & model_centers,
00241                         int & grid_center_x, int & grid_center_y);
00242         typename pcl17::PointCloud<PointT>::Ptr findLocalMaximaInGrid(
00243                         Eigen::MatrixXf grid, float window_size);
00244         vector<boost::shared_ptr<std::vector<int> > >
00245         findVotedSegments(typename pcl17::PointCloud<PointT>::Ptr local_maxima_,
00246                         const string & class_name, float window_size);
00247         void fitModelsWithRansac(
00248                         vector<boost::shared_ptr<std::vector<int> > > & voted_segments_,
00249                         const string class_name,
00250                         RandomSampleConsensusSimple<PointNormalT> & ransac,
00251                         vector<PointNormalCloudPtr> & result_, vector<float> & scores_);
00252         void generateVisibilityScore(vector<PointNormalCloudPtr> & result_,
00253                         vector<float> & scores_);
00254         bool intersectXY(const pcl17::PointCloud<PointNormalT> & cloud1,
00255                         const pcl17::PointCloud<PointNormalT> & cloud2);
00256         vector<typename pcl17::PointCloud<PointNormalT>::Ptr> removeIntersecting(
00257                         vector<typename pcl17::PointCloud<PointNormalT>::Ptr> & result_,
00258                         vector<float> & scores_, vector<float> * selected_scores = NULL);
00259         typename Eigen::ArrayXXi getLocalMaximaGrid(Eigen::MatrixXf & grid,
00260                         float window_size);
00261 
00262 public:
00263 
00264         float subsampling_resolution_;
00265         bool mls_polynomial_fit_;
00266         int mls_polynomial_order_;
00267         float mls_search_radius_;
00268         int min_points_in_segment_;
00269         float rg_residual_threshold_;
00270         float rg_smoothness_threshold_;
00271         float fe_k_neighbours_;
00272         int num_clusters_;
00273         int num_neighbours_;
00274         float cell_size_;
00275         float local_maxima_threshold_;
00276         float window_size_;
00277 
00278         float ransac_distance_threshold_;
00279         float ransac_vis_score_weight_;
00280         int ransac_num_iter_;
00281         double icp_treshold_;
00282         int num_angles_;
00283 
00284         int icp_max_iterations_;
00285         float icp_max_correspondence_distance_;
00286 
00287         bool debug_;
00288         string debug_folder_;
00289         string database_dir_;
00290 
00291         FeatureEstimatorType feature_estimator_;
00292         MovingLeastSquaresType mls_;
00293 
00294         DatabaseType database_;
00295         typename pcl17::PointCloud<FeatureT>::Ptr database_features_cloud_;
00296 
00297         ModelMapType class_name_to_partial_views_map_;
00298         ModelMapType class_name_to_full_models_map_;
00299 
00300         vector<FeatureT> features_;
00301         PointCloud centroids_;
00302         vector<std::string> classes_;
00303         vector<PointNormalCloudPtr> segment_pointclouds_;
00304         vector<boost::shared_ptr<vector<int> > > segment_indices_;
00305 
00306         PointNormalCloudPtr scene_;
00307         PointNormalT min_scene_bound_, max_scene_bound_;
00308         map<string, pcl17::PointCloud<pcl17::PointXYZI> > votes_;
00309         map<string, vector<int> > voted_segment_idx_;
00310 
00311         map<string, float> ransac_result_threshold_;
00312 
00313         map<string, vector<PointNormalCloudPtr> > found_objects_;
00314 
00315         std::string external_classifier_;
00316 
00317         FeatureT min_;
00318         FeatureT max_;
00319 
00320 };
00321 
00322 template<class FeatureT>
00323 inline bool operator <(const FeatureT & f, const FeatureT & s) {
00324         int N = sizeof(f.histogram) / sizeof(float);
00325 
00326         std::vector<float> v_f(f.histogram, f.histogram + N), v_s(s.histogram,
00327                         s.histogram + N);
00328         return v_f < v_s;
00329 }
00330 
00331 template<class PT, class PNT, class FT>
00332 YAML::Emitter& operator <<(YAML::Emitter& out,
00333                 const pcl17::PHVObjectClassifier<PT, PNT, FT> & h) {
00334 
00335         out << YAML::BeginMap;
00336 
00337         out << YAML::Key << "subsampling_resolution";
00338         out << YAML::Value << h.subsampling_resolution_;
00339 
00340         out << YAML::Key << "mls_polynomial_fit";
00341         out << YAML::Value << h.mls_polynomial_fit_;
00342 
00343         out << YAML::Key << "mls_polynomial_order";
00344         out << YAML::Value << h.mls_polynomial_order_;
00345 
00346         out << YAML::Key << "mls_search_radius";
00347         out << YAML::Value << h.mls_search_radius_;
00348 
00349         out << YAML::Key << "min_points_in_segment";
00350         out << YAML::Value << h.min_points_in_segment_;
00351 
00352         out << YAML::Key << "rg_residual_threshold";
00353         out << YAML::Value << h.rg_residual_threshold_;
00354 
00355         out << YAML::Key << "rg_smoothness_threshold";
00356         out << YAML::Value << h.rg_smoothness_threshold_;
00357 
00358         out << YAML::Key << "fe_k_neighbours";
00359         out << YAML::Value << h.fe_k_neighbours_;
00360 
00361         out << YAML::Key << "num_clusters";
00362         out << YAML::Value << h.num_clusters_;
00363 
00364         out << YAML::Key << "num_neighbours";
00365         out << YAML::Value << h.num_neighbours_;
00366 
00367         out << YAML::Key << "cell_size";
00368         out << YAML::Value << h.cell_size_;
00369 
00370         out << YAML::Key << "local_maxima_threshold";
00371         out << YAML::Value << h.local_maxima_threshold_;
00372 
00373         out << YAML::Key << "ransac_distance_threshold";
00374         out << YAML::Value << h.ransac_distance_threshold_;
00375 
00376         out << YAML::Key << "ransac_vis_score_weight";
00377         out << YAML::Value << h.ransac_vis_score_weight_;
00378 
00379         out << YAML::Key << "ransac_num_iter";
00380         out << YAML::Value << h.ransac_num_iter_;
00381 
00382         out << YAML::Key << "debug";
00383         out << YAML::Value << h.debug_;
00384 
00385         out << YAML::Key << "debug_folder";
00386         out << YAML::Value << h.debug_folder_;
00387 
00388         out << YAML::Key << "ransac_result_threshold";
00389         out << YAML::Value << h.ransac_result_threshold_;
00390 
00391         out << YAML::Key << "icp_treshold";
00392         out << YAML::Value << h.icp_treshold_;
00393 
00394         out << YAML::Key << "num_angles";
00395         out << YAML::Value << h.num_angles_;
00396 
00397         out << YAML::Key << "icp_max_iterations";
00398         out << YAML::Value << h.icp_max_iterations_;
00399 
00400         out << YAML::Key << "icp_max_correspondence_distance";
00401         out << YAML::Value << h.icp_max_correspondence_distance_;
00402 
00403         out << YAML::Key << "window_size";
00404         out << YAML::Value << h.window_size_;
00405 
00406         out << YAML::Key << "external_classifier";
00407         out << YAML::Value << h.external_classifier_;
00408 
00409         out << YAML::Key << "database";
00410         out << YAML::Value << h.database_;
00411 
00412         out << YAML::Key << "min_feature";
00413         out << YAML::Value << h.min_;
00414 
00415         out << YAML::Key << "max_feature";
00416         out << YAML::Value << h.max_;
00417         out << YAML::Key << "full_models";
00418 
00419         out << YAML::Value;
00420         out << YAML::BeginMap;
00421 
00422         typedef typename pcl17::PHVObjectClassifier<PT, PNT, FT>::ModelMapValueType M;
00423 
00424         BOOST_FOREACH(M v, h.class_name_to_full_models_map_) {
00425                 out << YAML::Key << v.first;
00426                 out << YAML::Value << YAML::BeginSeq;
00427 
00428                 for (size_t i = 0; i < v.second.size(); i++) {
00429                         std::stringstream ss;
00430                         ss << "models/" << v.first << i << ".pcd";
00431                         pcl17::io::savePCDFileASCII(h.database_dir_ + ss.str(),
00432                                         *v.second[i]);
00433                         out << ss.str();
00434 
00435                 }
00436                 out << YAML::EndSeq;
00437 
00438         }
00439         out << YAML::EndMap;
00440 
00441         out << YAML::EndMap;
00442 
00443         return out;
00444 }
00445 
00446 template<int N>
00447 YAML::Emitter& operator <<(YAML::Emitter& out, const pcl17::Histogram<N> & h) {
00448         out << YAML::Flow << YAML::BeginSeq;
00449         for (int j = 0; j < N; j++) {
00450                 out << h.histogram[j];
00451         }
00452         out << YAML::EndSeq << YAML::Block;
00453         return out;
00454 }
00455 
00456 template<int N>
00457 void operator >>(const YAML::Node& node, pcl17::Histogram<N> & h) {
00458         for (int j = 0; j < N; j++) {
00459                 node[j] >> h.histogram[j];
00460         }
00461 }
00462 
00463 YAML::Emitter& operator <<(YAML::Emitter& out,
00464                 const pcl17::ESFSignature640 & h) {
00465         out << YAML::BeginSeq;
00466         for (int j = 0; j < 640; j++) {
00467                 out << h.histogram[j];
00468         }
00469         out << YAML::EndSeq;
00470         return out;
00471 }
00472 
00473 void operator >>(const YAML::Node& node, pcl17::ESFSignature640 & h) {
00474         for (int j = 0; j < 640; j++) {
00475                 node[j] >> h.histogram[j];
00476         }
00477 }
00478 
00479 YAML::Emitter& operator <<(YAML::Emitter& out,
00480                 const pcl17::VFHSignature308 & h) {
00481         out << YAML::Flow << YAML::BeginSeq;
00482         for (int j = 0; j < 308; j++) {
00483                 out << h.histogram[j];
00484         }
00485         out << YAML::EndSeq << YAML::Block;
00486         return out;
00487 }
00488 
00489 void operator >>(const YAML::Node& node, pcl17::VFHSignature308 & h) {
00490         for (int j = 0; j < 308; j++) {
00491                 node[j] >> h.histogram[j];
00492         }
00493 }
00494 
00495 YAML::Emitter& operator <<(YAML::Emitter& out,
00496                 const pcl17::PointCloud<pcl17::ESFSignature640> & cloud) {
00497         out << YAML::Flow << YAML::BeginSeq;
00498         for (size_t i = 0; i < cloud.points.size(); i++) {
00499                 out << cloud.points[i];
00500         }
00501         out << YAML::EndSeq << YAML::Block;
00502 
00503         return out;
00504 }
00505 
00506 void operator >>(const YAML::Node& node,
00507                 pcl17::PointCloud<pcl17::ESFSignature640> & cloud) {
00508         cloud.clear();
00509 
00510         for (size_t i = 0; i < node.size(); i++) {
00511                 pcl17::ESFSignature640 point;
00512                 node[i]["cluster_center"] >> point;
00513                 cloud.points.push_back(point);
00514 
00515         }
00516 
00517         cloud.width = cloud.points.size();
00518         cloud.height = 1;
00519         cloud.is_dense = true;
00520 }
00521 
00522 YAML::Emitter& operator <<(YAML::Emitter& out,
00523                 const pcl17::PointCloud<pcl17::VFHSignature308> & cloud) {
00524         out << YAML::BeginSeq;
00525         for (size_t i = 0; i < cloud.points.size(); i++) {
00526                 out << cloud.points[i];
00527         }
00528         out << YAML::EndSeq;
00529 
00530         return out;
00531 }
00532 
00533 void operator >>(const YAML::Node& node,
00534                 pcl17::PointCloud<pcl17::VFHSignature308> & cloud) {
00535         cloud.clear();
00536 
00537         for (size_t i = 0; i < node.size(); i++) {
00538                 pcl17::VFHSignature308 point;
00539                 node[i]["cluster_center"] >> point;
00540                 cloud.points.push_back(point);
00541 
00542         }
00543 
00544         cloud.width = cloud.points.size();
00545         cloud.height = 1;
00546         cloud.is_dense = true;
00547 }
00548 
00549 template<typename PointT>
00550 YAML::Emitter& operator <<(YAML::Emitter& out,
00551                 const pcl17::PointCloud<PointT> & cloud) {
00552         out << YAML::BeginSeq;
00553         for (size_t i = 0; i < cloud.points.size(); i++) {
00554                 out << YAML::Flow << YAML::BeginSeq << cloud.points[i].x
00555                                 << cloud.points[i].y << cloud.points[i].z << YAML::EndSeq
00556                                 << YAML::Block;
00557         }
00558         out << YAML::EndSeq;
00559 
00560         return out;
00561 }
00562 
00563 template<typename PointT>
00564 void operator >>(const YAML::Node& node, pcl17::PointCloud<PointT> & cloud) {
00565         cloud.clear();
00566 
00567         for (size_t i = 0; i < node.size(); i++) {
00568                 PointT point;
00569                 node[i][0] >> point.x;
00570                 node[i][1] >> point.y;
00571                 node[i][2] >> point.z;
00572                 cloud.points.push_back(point);
00573 
00574         }
00575 
00576         cloud.width = cloud.points.size();
00577         cloud.height = 1;
00578         cloud.is_dense = true;
00579 }
00580 
00581 template<class PointT, class FeatureT>
00582 YAML::Emitter& operator <<(YAML::Emitter& out,
00583                 const map<FeatureT, map<string, pcl17::PointCloud<PointT> > > & database) {
00584         out << YAML::BeginSeq;
00585 
00586         for (typename map<FeatureT, map<string, pcl17::PointCloud<PointT> > >::const_iterator it =
00587                         database.begin(); it != database.end(); it++) {
00588                 FeatureT cluster_center = it->first;
00589                 map<string, pcl17::PointCloud<PointT> > class_centroid_map = it->second;
00590 
00591                 out << YAML::BeginMap;
00592                 out << YAML::Key << "cluster_center";
00593                 out << YAML::Value << cluster_center;
00594 
00595                 out << YAML::Key << "classes";
00596                 out << YAML::Value << YAML::BeginSeq;
00597 
00598                 for (typename map<string, pcl17::PointCloud<PointT> >::const_iterator it2 =
00599                                 class_centroid_map.begin(); it2 != class_centroid_map.end();
00600                                 it2++) {
00601                         std::string class_name = it2->first;
00602                         pcl17::PointCloud<PointT> centroids = it2->second;
00603                         out << YAML::BeginMap << YAML::Key << "class_name";
00604                         out << YAML::Value << class_name;
00605                         out << YAML::Key << "centroids";
00606                         out << YAML::Value << centroids;
00607                         out << YAML::EndMap;
00608 
00609                 }
00610 
00611                 out << YAML::EndSeq;
00612 
00613                 out << YAML::EndMap;
00614         }
00615 
00616         out << YAML::EndSeq;
00617         return out;
00618 }
00619 
00620 template<class PointT, class FeatureT>
00621 void operator >>(const YAML::Node& node,
00622                 map<FeatureT, map<string, pcl17::PointCloud<PointT> > > & database) {
00623         for (size_t i = 0; i < node.size(); i++) {
00624                 FeatureT cluster_center;
00625                 node[i]["cluster_center"] >> cluster_center;
00626 
00627                 for (size_t j = 0; j < node[i]["classes"].size(); j++) {
00628                         std::string class_name;
00629                         node[i]["classes"][j]["class_name"] >> class_name;
00630                         node[i]["classes"][j]["centroids"]
00631                                         >> database[cluster_center][class_name];
00632                 }
00633         }
00634 }
00635 
00636 template<class PT, class PNT, class FT>
00637 void operator >>(const YAML::Node& node,
00638                 pcl17::PHVObjectClassifier<PT, PNT, FT> & h) {
00639         node["subsampling_resolution"] >> h.subsampling_resolution_;
00640         node["mls_polynomial_fit"] >> h.mls_polynomial_fit_;
00641         node["mls_polynomial_order"] >> h.mls_polynomial_order_;
00642         node["mls_search_radius"] >> h.mls_search_radius_;
00643         node["min_points_in_segment"] >> h.min_points_in_segment_;
00644         node["rg_residual_threshold"] >> h.rg_residual_threshold_;
00645         node["rg_smoothness_threshold"] >> h.rg_smoothness_threshold_;
00646         node["external_classifier"] >> h.external_classifier_;
00647 
00648         node["fe_k_neighbours"] >> h.fe_k_neighbours_;
00649         node["num_clusters"] >> h.num_clusters_;
00650 
00651         node["num_neighbours"] >> h.num_neighbours_;
00652         node["cell_size"] >> h.cell_size_;
00653         node["local_maxima_threshold"] >> h.local_maxima_threshold_;
00654 
00655         node["ransac_distance_threshold"] >> h.ransac_distance_threshold_;
00656         node["ransac_vis_score_weight"] >> h.ransac_vis_score_weight_;
00657         node["ransac_num_iter"] >> h.ransac_num_iter_;
00658         node["ransac_result_threshold"] >> h.ransac_result_threshold_;
00659 
00660         node["icp_treshold"] >> h.icp_treshold_;
00661         node["num_angles"] >> h.num_angles_;
00662         node["window_size"] >> h.window_size_;
00663 
00664         node["icp_max_iterations"] >> h.icp_max_iterations_;
00665         node["icp_max_correspondence_distance"] >> h.icp_max_correspondence_distance_;
00666 
00667         node["debug"] >> h.debug_;
00668         node["debug_folder"] >> h.debug_folder_;
00669 
00670         node["min_feature"] >> h.min_;
00671         node["max_feature"] >> h.max_;
00672 
00673         node["database"] >> h.database_;
00674         node["database"] >> *(h.database_features_cloud_);
00675 
00676         map<string, vector<string> > full_models_locations;
00677         node["full_models"] >> full_models_locations;
00678 
00679         typedef map<string, vector<string> >::value_type vt;
00680 
00681         BOOST_FOREACH (vt &v, full_models_locations) {
00682                 for (size_t i = 0; i < v.second.size(); i++) {
00683                         typename PointCloud<PNT>::Ptr cloud(new PointCloud<PNT>);
00684                         pcl17::io::loadPCDFile(h.database_dir_ + v.second[i], *cloud);
00685                         h.class_name_to_full_models_map_[v.first].push_back(cloud);
00686 
00687                 }
00688 
00689         }
00690 
00691 }
00692 
00693 template<int N>
00694 void operator >>(const YAML::Node& node,
00695                 pcl17::PointCloud<pcl17::Histogram<N> > & feature_cloud) {
00696 
00697         for (size_t i = 0; i < node.size(); i++) {
00698                 pcl17::Histogram<N> cluster_center;
00699                 node[i]["cluster_center"] >> cluster_center;
00700                 feature_cloud.points.push_back(cluster_center);
00701         }
00702         feature_cloud.width = feature_cloud.points.size();
00703         feature_cloud.height = 1;
00704         feature_cloud.is_dense = true;
00705 }
00706 
00707 }
00708 
00709 #endif /* PHVOBJECTCLASSIFIER_H_ */
 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