$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_fs/common_io.h> 00009 00010 //Class that implements the functionality of vfh_recognition::VFHRecognizer 00011 //for the file system structures containing VFHS, views and so on... 00012 00013 namespace vfh_recognizer_fs 00014 { 00015 template<template<class > class Distance> 00016 class VFHRecognizerFS : public vfh_recognition::VFHRecognizer<Distance> 00017 { 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 private: 00027 00028 std::string root_dir; 00029 00030 bool 00031 getPointCloudFromId (pcl::PointCloud<pcl::PointNormal> & cloud, std::string id); 00032 00033 bool 00034 getVFHRollOrientationFromId (pcl::PointCloud<pcl::VFHSignature308> & vfh_orientation_signature, std::string id); 00035 00036 bool 00037 getPoseFromId(std::string id, geometry_msgs::Pose & pose); 00038 00039 std::string 00040 getModelId (std::string id); 00041 00042 int 00043 getVFHId (std::string id); 00044 00045 bool 00046 getVFHRollOrientationFromIdThroughView (pcl::PointCloud<pcl::VFHSignature308> & vfh_orientation_signature, std::string id); 00047 00048 bool 00049 getVFHCentroidFromVFHid (std::vector<float> & centroid, std::string id); 00050 00051 bool 00052 getViewCentroidFromVFHid (std::vector<float> & centroid, std::string id); 00053 00054 public: 00055 00056 bool 00057 getVFHHistogramFromVFHId (pcl::PointCloud<pcl::VFHSignature308> & vfh_descriptor, std::string vfh_id); 00058 00060 00065 bool 00066 initialize (bool useDB, bf::path dpath, std::string root_dir, int linear = 0); 00067 00069 00073 bool 00074 detect (const sensor_msgs::PointCloud2ConstPtr& msg, int nModels, std::vector<std::string>& model_ids, std::vector< 00075 geometry_msgs::Pose> & poses, std::vector<float>& confidences, bool use_fitness_score = true); 00076 }; 00077 00078 }