$search
00001 #include <vfh_recognition/vfh_recognition.h> 00002 00003 #include "household_objects_database/database_view.h" 00004 #include "household_objects_database/database_vfh.h" 00005 #include "household_objects_database/objects_database.h" 00006 #include "household_objects_database/database_helper_classes.h" 00007 00008 #include <vfh_recognizer_db/common_io.h> 00009 00010 //Class that implements the functionality of vfh_recognition::VFHRecognizer 00011 //for the household_objects_database, creating kdtree from the db, 00012 //loading views from the db, etc. 00013 00014 namespace vfh_recognizer_db 00015 { 00016 template<template<class > class Distance> 00017 class VFHRecognizerDB : public vfh_recognition::VFHRecognizer<Distance> 00018 { 00019 typedef vfh_recognition::VFHRecognizer<Distance> base_t; 00020 using base_t::models_; 00021 using base_t::data_; 00022 using base_t::index_; 00023 00024 typedef Distance<float> DistT; 00025 00026 public: 00027 VFHRecognizerDB (bool enable_cache = false) : cache_enabled_(enable_cache) {} 00028 bool isCacheEnabled () {return cache_enabled_;} 00029 void setCacheEnabled (bool e) {cache_enabled_ = e;} 00030 00031 private: 00032 00033 household_objects_database::ObjectsDatabase * database; 00034 00035 bool 00036 getPointCloudFromId (pcl::PointCloud<pcl::PointNormal> & cloud, std::string id); 00037 00038 bool 00039 getVFHRollOrientationFromId (pcl::PointCloud<pcl::VFHSignature308> & vfh_orientation_signature, std::string id); 00040 00041 bool 00042 getVFHRollOrientationFromIdThroughView (pcl::PointCloud<pcl::VFHSignature308> & vfh_orientation_signature, std::string id); 00043 00044 bool 00045 getVFHCentroidFromVFHid (std::vector<float> & centroid, std::string id); 00046 00047 bool 00048 getViewCentroidFromVFHid (std::vector<float> & centroid, std::string id); 00049 00050 bool 00051 getPoseFromId(std::string id, geometry_msgs::Pose & pose); 00052 00053 std::string 00054 getModelId (std::string id); 00055 00056 int 00057 getVFHId (std::string id); 00058 00059 public: 00060 00061 inline int buildTreeFromViews (std::vector<boost::shared_ptr<household_objects_database::DatabaseView> > & views); 00062 00063 inline bool buildTreeFromDB (int iteration); 00064 inline bool buildCachesFromDB (bf::path dpath, int iteration); 00065 00066 bool 00067 getVFHHistogramFromVFHId (pcl::PointCloud<pcl::VFHSignature308> & vfh_descriptor, std::string vfh_id); 00068 00069 int initializeFromViews(std::vector<boost::shared_ptr<household_objects_database::DatabaseView> > & views); 00070 00072 00077 bool 00078 initialize (bool useDB, bf::path dpath, int linear = 0, int iteration = 0, bool no_save = false); 00079 00081 00085 bool 00086 detect (const sensor_msgs::PointCloud2ConstPtr& msg, int nModels, std::vector<int>& model_ids, std::vector< 00087 geometry_msgs::Pose> & poses, std::vector<float>& confidences, bool use_fitness_score = true, std::vector< 00088 boost::shared_ptr<household_objects_database::DatabaseView> > * views = NULL, std::vector<std::string> * vfh_ids_vec = NULL); 00089 00090 00091 bool cache_enabled_; 00092 std::map <int, pcl::PointCloud<pcl::VFHSignature308>, std::less<int>, Eigen::aligned_allocator<pcl::VFHSignature308> > roll_cache_; 00093 std::map <int, pcl::PointCloud<pcl::VFHSignature308>, std::less<int>, Eigen::aligned_allocator<pcl::VFHSignature308> > vfh_cache_; 00094 std::map <int, pcl::PointCloud<pcl::PointNormal>, std::less<int>, Eigen::aligned_allocator<pcl::PointNormal> > view_cache_; 00095 std::map <int, std::vector<float> > cluster_centroids_cache_; 00096 std::map <int, geometry_msgs::Pose > pose_cache_; 00097 std::map <int, std::string > scaled_model_id_cache_; 00098 }; 00099 00100 }