$search
00001 #include "vfh_recognizer_db/vfh_recognition.h" 00002 #include <pcl/filters/statistical_outlier_removal.h> 00003 #include <pcl/filters/radius_outlier_removal.h> 00004 00005 namespace vfh_recognizer_db 00006 { 00007 template<template<class > class Distance> 00008 bool 00009 VFHRecognizerDB<Distance>::getPointCloudFromId (pcl::PointCloud<pcl::PointNormal> & cloud, std::string vfh_id) 00010 { 00011 if (cache_enabled_) 00012 { 00013 std::map<int, pcl::PointCloud<pcl::PointNormal> >::iterator it = view_cache_.find (atoi (vfh_id.c_str ())); 00014 00015 if (it != view_cache_.end ()) 00016 { 00017 cloud = it->second; 00018 return (true); 00019 } 00020 } 00021 00022 boost::shared_ptr<household_objects_database::DatabaseView> view; 00023 00024 if (!database->getViewFromVFHId (atoi (vfh_id.c_str ()), view)) 00025 return (false); 00026 00027 boost::shared_array<uint8_t> bufferRead (new uint8_t[view->view_point_cloud_data_.data ().size ()]); 00028 memcpy (&bufferRead[0], &(view->view_point_cloud_data_.data ()[0]), view->view_point_cloud_data_.data ().size ()); 00029 ser::IStream streamIn (bufferRead.get (), view->view_point_cloud_data_.data ().size ()); 00030 ser::deserialize (streamIn, cloud); 00031 00032 return (true); 00033 } 00034 00035 template<template<class > class Distance> 00036 bool 00037 VFHRecognizerDB<Distance>::getVFHHistogramFromVFHId (pcl::PointCloud<pcl::VFHSignature308> & vfh_descriptor, 00038 std::string vfh_id) 00039 { 00040 00041 std::map<int, pcl::PointCloud<pcl::VFHSignature308> >::iterator it = vfh_cache_.find (atoi (vfh_id.c_str ())); 00042 00043 if (it != vfh_cache_.end ()) 00044 { 00045 vfh_descriptor = it->second; 00046 return (true); 00047 } 00048 00049 std::vector<boost::shared_ptr<household_objects_database::DatabaseVFH> > vfhs; 00050 std::stringstream where; 00051 where << "vfh_id =" << vfh_id; 00052 std::string where_clause (where.str ()); 00053 if (!database->getList (vfhs, where_clause)) 00054 { 00055 return false; 00056 } 00057 00058 if (!database->loadFromDatabase (&vfhs[0]->vfh_descriptor_)) 00059 { 00060 ROS_ERROR ("Failed to load VFH descriptor with id %s", vfh_id.c_str ()); 00061 } 00062 00063 boost::shared_array<uint8_t> bufferRead (new uint8_t[vfhs[0]->vfh_descriptor_.data ().size ()]); 00064 memcpy (&bufferRead[0], &(vfhs[0]->vfh_descriptor_.data ()[0]), vfhs[0]->vfh_descriptor_.data ().size ()); 00065 ser::IStream streamIn (bufferRead.get (), vfhs[0]->vfh_descriptor_.data ().size ()); 00066 ser::deserialize (streamIn, vfh_descriptor); 00067 00068 return true; 00069 } 00070 00071 template<template<class > class Distance> 00072 bool 00073 VFHRecognizerDB<Distance>::getVFHCentroidFromVFHid (std::vector<float> & centroid, std::string id) 00074 { 00075 00076 std::map<int, std::vector<float> >::iterator it = cluster_centroids_cache_.find (atoi (id.c_str ())); 00077 00078 if (it != cluster_centroids_cache_.end ()) 00079 { 00080 centroid = it->second; 00081 return (true); 00082 } 00083 00084 std::vector<boost::shared_ptr<household_objects_database::DatabaseVFH> > vfhs; 00085 std::stringstream where; 00086 where << "vfh_id =" << id; 00087 std::string where_clause (where.str ()); 00088 if (!database->getList (vfhs, where_clause)) 00089 { 00090 return false; 00091 } 00092 00093 centroid = vfhs[0]->centroid_.data (); 00094 return true; 00095 } 00096 00097 template<template<class > class Distance> 00098 bool 00099 VFHRecognizerDB<Distance>::getViewCentroidFromVFHid (std::vector<float> & centroid, std::string id) 00100 { 00101 boost::shared_ptr<household_objects_database::DatabaseView> view; 00102 00103 if (!database->getViewFromVFHId (atoi (id.c_str ()), view)) 00104 return (false); 00105 00106 centroid = view->centroid_.data (); 00107 return true; 00108 } 00109 00110 template<template<class > class Distance> 00111 bool 00112 VFHRecognizerDB<Distance>::getVFHRollOrientationFromId ( 00113 pcl::PointCloud<pcl::VFHSignature308> & vfh_orientation_signature, 00114 std::string vfh_id) 00115 { 00116 if (cache_enabled_) 00117 { 00118 std::map<int, pcl::PointCloud<pcl::VFHSignature308> >::iterator it = roll_cache_.find (atoi (vfh_id.c_str ())); 00119 00120 if (it != roll_cache_.end ()) 00121 { 00122 vfh_orientation_signature = it->second; 00123 return (true); 00124 } 00125 } 00126 00127 boost::shared_ptr<household_objects_database::DatabaseVFHOrientation> roll_histogram; 00128 if (!database->getOrientationRollFromVFHId (atoi (vfh_id.c_str ()), roll_histogram)) 00129 return (false); 00130 00131 boost::shared_array<uint8_t> bufferRead (new uint8_t[roll_histogram->vfh_orientation_descriptor_.data ().size ()]); 00132 memcpy (&bufferRead[0], &(roll_histogram->vfh_orientation_descriptor_.data ()[0]), 00133 roll_histogram->vfh_orientation_descriptor_.data ().size ()); 00134 ser::IStream streamIn (bufferRead.get (), roll_histogram->vfh_orientation_descriptor_.data ().size ()); 00135 ser::deserialize (streamIn, vfh_orientation_signature); 00136 00137 return (true); 00138 } 00139 00140 template<template<class > class Distance> 00141 bool 00142 VFHRecognizerDB<Distance>::getVFHRollOrientationFromIdThroughView ( 00143 pcl::PointCloud<pcl::VFHSignature308> & vfh_orientation_signature, 00144 std::string vfh_id) 00145 { 00146 if (cache_enabled_) 00147 { 00148 std::map<int, pcl::PointCloud<pcl::VFHSignature308> >::iterator it = roll_cache_.find (atoi (vfh_id.c_str ())); 00149 00150 if (it != roll_cache_.end ()) 00151 { 00152 vfh_orientation_signature = it->second; 00153 return (true); 00154 } 00155 } 00156 00157 boost::shared_ptr<household_objects_database::DatabaseVFHOrientation> roll_histogram; 00158 if (!database->getOrientationRollFromVFHThroughViewId (atoi (vfh_id.c_str ()), roll_histogram)) 00159 return (false); 00160 00161 boost::shared_array<uint8_t> bufferRead (new uint8_t[roll_histogram->vfh_orientation_descriptor_.data ().size ()]); 00162 memcpy (&bufferRead[0], &(roll_histogram->vfh_orientation_descriptor_.data ()[0]), 00163 roll_histogram->vfh_orientation_descriptor_.data ().size ()); 00164 ser::IStream streamIn (bufferRead.get (), roll_histogram->vfh_orientation_descriptor_.data ().size ()); 00165 ser::deserialize (streamIn, vfh_orientation_signature); 00166 00167 return (true); 00168 } 00169 00170 template<template<class > class Distance> 00171 int 00172 VFHRecognizerDB<Distance>::getVFHId (std::string id) 00173 { 00174 return atoi (id.c_str ()); 00175 } 00176 ; 00177 00178 template<template<class > class Distance> 00179 bool 00180 VFHRecognizerDB<Distance>::getPoseFromId (std::string id, geometry_msgs::Pose & pose) 00181 { 00182 00183 std::map<int, geometry_msgs::Pose>::iterator it = pose_cache_.find (atoi (id.c_str ())); 00184 00185 if (it != pose_cache_.end ()) 00186 { 00187 pose = it->second; 00188 return (true); 00189 } 00190 00191 boost::shared_ptr<household_objects_database::DatabaseView> view; 00192 if (!database->getViewFromVFHIdNoData (atoi (id.c_str ()), view)) 00193 return (false); 00194 00195 pose = view->view_transform_.data ().pose_; 00196 return true; 00197 } 00198 00199 template<template<class > class Distance> 00200 std::string 00201 VFHRecognizerDB<Distance>::getModelId (std::string id) 00202 { 00203 00204 std::map<int, std::string>::iterator it = scaled_model_id_cache_.find (atoi (id.c_str ())); 00205 00206 if (it != scaled_model_id_cache_.end ()) 00207 { 00208 return it->second; 00209 } 00210 00211 boost::shared_ptr<household_objects_database::DatabaseView> view; 00212 if (!database->getViewFromVFHIdNoData (atoi (id.c_str ()), view)) 00213 return (false); 00214 00215 std::stringstream model_id; 00216 model_id << view->scaled_model_id_.data (); 00217 return model_id.str (); 00218 } 00219 00220 template<template<class > class Distance> 00221 int 00222 VFHRecognizerDB<Distance>::initializeFromViews (std::vector<boost::shared_ptr< 00223 household_objects_database::DatabaseView> > & views) 00224 { 00225 int minid = buildTreeFromViews (views); 00226 index_ = new flann::Index<DistT> (data_, flann::LinearIndexParams ()); 00227 index_->buildIndex (); 00228 return minid; 00229 } 00230 00231 template<template<class > class Distance> 00232 bool 00233 VFHRecognizerDB<Distance>::initialize (bool useDB, bf::path dpath, int linear, int iteration, bool no_save) 00234 { 00235 00236 //cache from DB poses, ids and centroids... 00237 household_objects_database::ObjectsDatabase database_init ("wgs36.willowgarage.com", "5432", "willow", "willow", 00238 "household_objects"); 00239 00240 if (!database_init.isConnected ()) 00241 { 00242 std::cerr << "Database failed to connect \n"; 00243 return false; 00244 } 00245 std::cerr << "Database connected successfully \n"; 00246 00247 //Read VFH descriptor and build tree... 00248 std::vector<boost::shared_ptr<household_objects_database::DatabaseVFH> > vfhs; 00249 std::stringstream where; 00250 where << "iteration = " << iteration; 00251 std::string where_clause (where.str ()); 00252 database_init.getList (vfhs, where_clause); 00253 std::cerr << "Number of vfhs:" << vfhs.size () << "\n"; 00254 00255 for (size_t i = 0; i < vfhs.size (); i++) 00256 { 00257 cluster_centroids_cache_[vfhs[i]->vfh_id_.data ()] = vfhs[i]->centroid_.data (); 00258 std::cout << "Loading cluster" << i << std::endl; 00259 00260 boost::shared_ptr<household_objects_database::DatabaseView> view; 00261 if (!database_init.getViewFromVFHIdNoData (vfhs[i]->vfh_id_.data (), view)) 00262 ROS_WARN ("No view returned"); 00263 00264 pose_cache_[vfhs[i]->vfh_id_.data ()] = view->view_transform_.data ().pose_; 00265 00266 std::stringstream model_id; 00267 model_id << view->scaled_model_id_.data (); 00268 scaled_model_id_cache_[vfhs[i]->vfh_id_.data ()] = model_id.str (); 00269 00270 //cache also the VFH descriptor 00271 if (!database_init.loadFromDatabase (&vfhs[i]->vfh_descriptor_)) 00272 { 00273 ROS_ERROR ("Failed to load VFH descriptor"); 00274 } 00275 00276 pcl::PointCloud < pcl::VFHSignature308 > vfh_descriptor; 00277 boost::shared_array<uint8_t> bufferRead (new uint8_t[vfhs[i]->vfh_descriptor_.data ().size ()]); 00278 memcpy (&bufferRead[0], &(vfhs[i]->vfh_descriptor_.data ()[0]), vfhs[i]->vfh_descriptor_.data ().size ()); 00279 ser::IStream streamIn (bufferRead.get (), vfhs[i]->vfh_descriptor_.data ().size ()); 00280 ser::deserialize (streamIn, vfh_descriptor); 00281 vfh_cache_[vfhs[i]->vfh_id_.data ()] = vfh_descriptor; 00282 00283 } 00284 00285 bf::path training_data_h5_file_name = dpath / "training_data.h5"; 00286 bf::path training_data_list_file_name = dpath / "training_data.list"; 00287 bf::path index_filename = dpath / "kdtree.idx"; 00288 00289 if (useDB || !boost::filesystem::exists (training_data_h5_file_name) 00290 || !boost::filesystem::exists (training_data_list_file_name) || !boost::filesystem::exists (index_filename)) 00291 { 00292 //read training data from DB and build kdtree 00293 buildTreeFromDB (iteration); 00294 std::cout << "Tree build from DB:" << models_.size () << " " << data_.rows << std::endl; 00295 index_ = new flann::Index<DistT> (data_, flann::LinearIndexParams ()); 00296 index_->buildIndex (); 00297 00298 if (useDB && !no_save) 00299 { 00300 //files could exists, try to delete them 00301 if (boost::filesystem::exists (training_data_h5_file_name)) 00302 boost::filesystem::remove (training_data_h5_file_name); 00303 00304 if (boost::filesystem::exists (training_data_list_file_name)) 00305 boost::filesystem::remove (training_data_list_file_name); 00306 00307 if (boost::filesystem::exists (index_filename)) 00308 boost::filesystem::remove (index_filename); 00309 } 00310 00311 if (!boost::filesystem::exists (dpath)) 00312 { 00313 ROS_WARN ("%s does not exist. Not able to save training_data!", dpath.string ().c_str ()); 00314 } 00315 else 00316 { 00317 if (no_save) 00318 { 00319 ROS_WARN ("Data wont be saved, user asked for that..."); 00320 } 00321 else 00322 { 00323 //SAVE the kdtree + training_list to the database 00324 flann::save_to_file (data_, training_data_h5_file_name.string ().c_str (), "training_data"); 00325 saveFileList (models_, training_data_list_file_name.string ().c_str ()); 00326 index_->save (index_filename.string ().c_str ()); 00327 } 00328 } 00329 } 00330 else 00331 { 00332 loadFileList (models_, training_data_list_file_name.string ()); 00333 flann::load_from_file (data_, training_data_h5_file_name.string (), "training_data"); 00334 index_ = new flann::Index<DistT> (data_, flann::SavedIndexParams (index_filename.string ().c_str ())); 00335 index_->buildIndex (); 00336 } 00337 00338 if (cache_enabled_) 00339 buildCachesFromDB (dpath, iteration); 00340 00341 //Connect to database 00342 database = new household_objects_database::ObjectsDatabase ("wgs36.willowgarage.com", "5432", "willow", "willow", 00343 "household_objects"); 00344 00345 return true; 00346 } 00347 00348 template<template<class > class Distance> 00349 bool 00350 VFHRecognizerDB<Distance>::detect (const sensor_msgs::PointCloud2ConstPtr& msg, int nModels, 00351 std::vector<int>& model_ids, std::vector<geometry_msgs::Pose> & poses, 00352 std::vector<float>& confidences, bool use_fitness_score, std::vector< 00353 boost::shared_ptr<household_objects_database::DatabaseView> >* views, 00354 std::vector<std::string> * vfh_ids_vec) 00355 { 00356 00357 std::vector<std::string> vfh_ids; 00358 std::vector<std::string> model_ids_string; 00359 00360 this->detect_ (msg, nModels, model_ids_string, poses, confidences, vfh_ids, use_fitness_score); 00361 00362 for (size_t i = 0; i < model_ids_string.size (); i++) 00363 { 00364 model_ids.push_back (atoi (model_ids_string[i].c_str ())); 00365 } 00366 00367 if (views != NULL) 00368 { 00369 for (size_t i = 0; i < vfh_ids.size (); i++) 00370 { 00371 boost::shared_ptr<household_objects_database::DatabaseView> view; 00372 database->getViewFromVFHId (atoi (vfh_ids[i].c_str ()), view); 00373 views->push_back (view); 00374 00375 if (vfh_ids_vec != NULL) 00376 { 00377 vfh_ids_vec->push_back (vfh_ids[i]); 00378 } 00379 } 00380 } 00381 00382 return true; 00383 } 00384 00385 template<template<class > class Distance> 00386 inline int 00387 VFHRecognizerDB<Distance>::buildTreeFromViews (std::vector< 00388 boost::shared_ptr<household_objects_database::DatabaseView> > & views) 00389 { 00390 household_objects_database::ObjectsDatabase database ("wgs36.willowgarage.com", "5432", "willow", "willow", 00391 "household_objects"); 00392 00393 if (!database.isConnected ()) 00394 { 00395 std::cerr << "Database failed to connect \n"; 00396 return -1; 00397 } 00398 std::cerr << "Database connected successfully" << views.size () << "\n"; 00399 00400 //get min-id 00401 int minid = std::numeric_limits<int>::max (); 00402 00403 for (size_t i = 0; i < views.size (); i++) 00404 { 00405 std::cerr << views[i]->view_id_.data () << "\n"; 00406 std::vector<boost::shared_ptr<household_objects_database::DatabaseVFH> > vfhs; 00407 std::stringstream where; 00408 where << "view_id = " << views[i]->view_id_.data (); 00409 std::string where_clause (where.str ()); 00410 database.getList (vfhs, where_clause); 00411 00412 if (!database.loadFromDatabase (&vfhs[0]->vfh_descriptor_)) 00413 std::cerr << "Load data failed\n"; 00414 else 00415 std::cerr << "Succeeded" << i << " " << vfhs[0]->vfh_descriptor_.data ().size () << std::endl; 00416 00417 if (vfhs[0]->vfh_descriptor_.data ().size () > 308 * sizeof(float)) 00418 { 00419 //deserialize vfh descriptor 00420 pcl::PointCloud < pcl::VFHSignature308 > vfh_signature; 00421 boost::shared_array<uint8_t> bufferRead (new uint8_t[vfhs[0]->vfh_descriptor_.data ().size ()]); 00422 memcpy (&bufferRead[0], &(vfhs[0]->vfh_descriptor_.data ()[0]), vfhs[0]->vfh_descriptor_.data ().size ()); 00423 ser::IStream streamIn (bufferRead.get (), vfhs[0]->vfh_descriptor_.data ().size ()); 00424 ser::deserialize (streamIn, vfh_signature); 00425 00426 std::stringstream vfh_id_str; 00427 vfh_id_str << vfhs[0]->vfh_id_.data (); 00428 std::cout << "vfh_id_str:" << vfh_id_str.str () << std::endl; 00429 00430 vfh_model_db vfh; 00431 vfh.first = vfh_id_str.str (); 00432 vfh.second.resize (308); 00433 memcpy (&vfh.second[0], &vfh_signature.points[0].histogram[0], 308 * sizeof(float)); 00434 models_.push_back (vfh); 00435 00436 minid = (std::min) (minid, vfhs[0]->vfh_id_.data ()); 00437 } 00438 } 00439 00440 convertToFLANN (models_, data_); 00441 return minid; 00442 } 00443 00444 template<template<class > class Distance> 00445 inline bool 00446 VFHRecognizerDB<Distance>::buildTreeFromDB (int iteration) 00447 { 00448 household_objects_database::ObjectsDatabase database ("wgs36.willowgarage.com", "5432", "willow", "willow", 00449 "household_objects"); 00450 00451 if (!database.isConnected ()) 00452 { 00453 std::cerr << "Database failed to connect \n"; 00454 return false; 00455 } 00456 std::cerr << "Database connected successfully \n"; 00457 00458 //Read VFH descriptor and build tree... 00459 std::vector<boost::shared_ptr<household_objects_database::DatabaseVFH> > vfhs; 00460 std::stringstream where; 00461 where << "iteration = " << iteration; 00462 std::string where_clause (where.str ()); 00463 database.getList (vfhs, where_clause); 00464 //database.getList (vfhs); 00465 std::cerr << "Number of vfhs:" << vfhs.size () << "\n"; 00466 00467 for (size_t i = 0; i < vfhs.size (); i++) 00468 { 00469 if (!database.loadFromDatabase (&vfhs[i]->vfh_descriptor_)) 00470 std::cerr << "Load data failed\n"; 00471 else 00472 std::cerr << "Succeeded" << i << " " << vfhs[i]->vfh_descriptor_.data ().size () << std::endl; 00473 00474 if (vfhs[i]->vfh_descriptor_.data ().size () > 308 * sizeof(float)) 00475 { 00476 //deserialize vfh descriptor 00477 pcl::PointCloud < pcl::VFHSignature308 > vfh_signature; 00478 boost::shared_array<uint8_t> bufferRead (new uint8_t[vfhs[i]->vfh_descriptor_.data ().size ()]); 00479 memcpy (&bufferRead[0], &(vfhs[i]->vfh_descriptor_.data ()[0]), vfhs[i]->vfh_descriptor_.data ().size ()); 00480 ser::IStream streamIn (bufferRead.get (), vfhs[i]->vfh_descriptor_.data ().size ()); 00481 ser::deserialize (streamIn, vfh_signature); 00482 00483 std::stringstream vfh_id_str; 00484 vfh_id_str << vfhs[i]->vfh_id_.data (); 00485 00486 vfh_model_db vfh; 00487 vfh.first = vfh_id_str.str (); 00488 vfh.second.resize (308); 00489 memcpy (&vfh.second[0], &vfh_signature.points[0].histogram[0], 308 * sizeof(float)); 00490 models_.push_back (vfh); 00491 } 00492 } 00493 00494 convertToFLANN (models_, data_); 00495 return true; 00496 } 00497 00498 template<template<class > class Distance> 00499 inline bool 00500 VFHRecognizerDB<Distance>::buildCachesFromDB (bf::path dpath, int iteration) 00501 { 00502 std::stringstream ss; 00503 ss << "iteration" << iteration; 00504 bf::path view_cache_dir = dpath / ss.str () / "views"; 00505 bf::path roll_cache_dir = dpath / ss.str () / "roll"; 00506 00507 std::cout << "buildCachesFromDB" << std::endl; 00508 00509 if (!boost::filesystem::exists (view_cache_dir) || !boost::filesystem::exists (roll_cache_dir)) 00510 { 00511 if (!bf::exists(dpath)) bf::create_directory (dpath); 00512 if (!bf::exists(dpath / ss.str())) bf::create_directory (dpath / ss.str() ); 00513 bf::create_directory (view_cache_dir); 00514 bf::create_directory (roll_cache_dir); 00515 std::cerr << "Building Caches from DB \n"; 00516 household_objects_database::ObjectsDatabase database ("wgs36.willowgarage.com", "5432", "willow", "willow", 00517 "household_objects"); 00518 00519 if (!database.isConnected ()) 00520 { 00521 std::cerr << "Database failed to connect \n"; 00522 return false; 00523 } 00524 std::cerr << "Database connected successfully \n"; 00525 00526 //Read VFH descriptor and build tree... 00527 std::vector<boost::shared_ptr<household_objects_database::DatabaseVFH> > vfhs; 00528 std::stringstream where; 00529 where << "iteration = " << iteration; 00530 std::string where_clause (where.str ()); 00531 database.getList (vfhs, where_clause); 00532 std::cerr << "Number of vfhs:" << vfhs.size () << "\n"; 00533 00534 for (size_t i = 0; i < vfhs.size (); i++) 00535 { 00536 // get view 00537 boost::shared_ptr<household_objects_database::DatabaseView> view; 00538 00539 if (database.getViewFromVFHId (vfhs[i]->vfh_id_.data (), view)) 00540 { 00541 std::cerr << "Writing view "; 00542 pcl::PointCloud < pcl::PointNormal > cloud; 00543 boost::shared_array<uint8_t> bufferRead (new uint8_t[view->view_point_cloud_data_.data ().size ()]); 00544 memcpy (&bufferRead[0], &(view->view_point_cloud_data_.data ()[0]), 00545 view->view_point_cloud_data_.data ().size ()); 00546 ser::IStream streamIn (bufferRead.get (), view->view_point_cloud_data_.data ().size ()); 00547 ser::deserialize (streamIn, cloud); 00548 std::stringstream file_name; 00549 file_name << view_cache_dir.string (); 00550 file_name << "/view_" << vfhs[i]->vfh_id_.data () << ".pcd"; 00551 std::cerr << file_name.str () << std::endl; 00552 pcl::io::savePCDFile (file_name.str (), cloud, true); 00553 view_cache_[vfhs[i]->vfh_id_.data ()] = cloud; 00554 } 00555 00556 // get roll hist 00557 boost::shared_ptr<household_objects_database::DatabaseVFHOrientation> roll_histogram; 00558 if (database.getOrientationRollFromVFHId (vfhs[i]->vfh_id_.data (), roll_histogram)) 00559 { 00560 std::cerr << "Writing roll "; 00561 pcl::PointCloud < pcl::VFHSignature308 > vfh_orientation_signature; 00562 boost::shared_array<uint8_t> 00563 bufferRead ( 00564 new uint8_t[roll_histogram->vfh_orientation_descriptor_.data ().size ()]); 00565 memcpy (&bufferRead[0], &(roll_histogram->vfh_orientation_descriptor_.data ()[0]), 00566 roll_histogram->vfh_orientation_descriptor_.data ().size ()); 00567 ser::IStream streamIn (bufferRead.get (), roll_histogram->vfh_orientation_descriptor_.data ().size ()); 00568 ser::deserialize (streamIn, vfh_orientation_signature); 00569 std::stringstream file_name; 00570 file_name << roll_cache_dir.string (); 00571 file_name << "/roll_" << vfhs[i]->vfh_id_.data () << ".pcd"; 00572 std::cerr << file_name.str () << std::endl; 00573 pcl::io::savePCDFile (file_name.str (), vfh_orientation_signature, true); 00574 roll_cache_[vfhs[i]->vfh_id_.data ()] = vfh_orientation_signature; 00575 } 00576 else 00577 { 00578 //if the roll is not found, we can search through view 00579 if (database.getOrientationRollFromVFHThroughViewId (vfhs[i]->vfh_id_.data (), roll_histogram)) 00580 { 00581 std::cerr << "Writing roll "; 00582 pcl::PointCloud < pcl::VFHSignature308 > vfh_orientation_signature; 00583 boost::shared_array<uint8_t> 00584 bufferRead ( 00585 new uint8_t[roll_histogram->vfh_orientation_descriptor_.data ().size ()]); 00586 memcpy (&bufferRead[0], &(roll_histogram->vfh_orientation_descriptor_.data ()[0]), 00587 roll_histogram->vfh_orientation_descriptor_.data ().size ()); 00588 ser::IStream streamIn (bufferRead.get (), roll_histogram->vfh_orientation_descriptor_.data ().size ()); 00589 ser::deserialize (streamIn, vfh_orientation_signature); 00590 std::stringstream file_name; 00591 file_name << roll_cache_dir.string (); 00592 file_name << "/roll_" << vfhs[i]->vfh_id_.data () << ".pcd"; 00593 std::cerr << file_name.str () << std::endl; 00594 pcl::io::savePCDFile (file_name.str (), vfh_orientation_signature, true); 00595 roll_cache_[vfhs[i]->vfh_id_.data ()] = vfh_orientation_signature; 00596 } 00597 } 00598 } 00599 } 00600 else 00601 { 00602 std::cerr << "Building Caches from filesystem : " << std::endl; 00603 // load from files ... 00604 bf::directory_iterator end_itr; 00605 pcl::PointCloud < pcl::PointNormal > cloud; 00606 pcl::PointCloud < pcl::VFHSignature308 > roll; 00607 for (bf::directory_iterator itr (view_cache_dir); itr != end_itr; ++itr) 00608 { 00609 if (!bf::is_directory (itr->status ())) 00610 { 00611 std::string full_file_name = itr->path ().string (); 00612 //std::cerr << "opening " << full_file_name.c_str() << std::endl; 00613 std::vector<std::string> strs; 00614 #if (!defined BOOST_FILESYSTEM_VERSION) || (BOOST_FILESYSTEM_VERSION<=2) 00615 std::string file_name = itr->path ().filename (); 00616 #else 00617 std::string file_name = itr->path ().filename ().string (); 00618 #endif 00619 boost::split (strs, file_name, boost::is_any_of ("_.")); 00620 if (strs.size () == 3) 00621 { 00622 if (strs[0] == "view") 00623 { 00624 pcl::io::loadPCDFile (full_file_name, cloud); 00625 view_cache_[atoi (strs[1].c_str ())] = cloud; 00626 } 00627 } 00628 } 00629 } 00630 for (bf::directory_iterator itr (roll_cache_dir); itr != end_itr; ++itr) 00631 { 00632 if (!bf::is_directory (itr->status ())) 00633 { 00634 std::string full_file_name = itr->path ().string (); 00635 #if (!defined BOOST_FILESYSTEM_VERSION) || (BOOST_FILESYSTEM_VERSION<=2) 00636 std::string file_name = itr->path ().filename (); 00637 #else 00638 std::string file_name = itr->path ().filename ().string (); 00639 #endif 00640 //std::cerr << "opening " << full_file_name.c_str() << std::endl; 00641 std::vector<std::string> strs; 00642 boost::split (strs, file_name, boost::is_any_of ("_.")); 00643 if (strs.size () == 3) 00644 { 00645 if (strs[0] == "roll") 00646 { 00647 pcl::io::loadPCDFile (full_file_name, roll); 00648 roll_cache_[atoi (strs[1].c_str ())] = roll; 00649 } 00650 } 00651 } 00652 } 00653 } 00654 std::cerr << "cache contains " << roll_cache_.size () << " roll histograms and " << view_cache_.size () 00655 << " views." << std::endl; 00656 00657 return true; 00658 } 00659 00660 template class VFHRecognizerDB<flann::ChiSquareDistance> ; 00661 template class VFHRecognizerDB<flann::L2> ; 00662 template class VFHRecognizerDB<flann::HistIntersectionDistance> ; 00663 template class VFHRecognizerDB<flann::HistIntersectionUnionDistance> ; 00664 }