$search
#include <vfh_recognition.h>
Public Member Functions | |
bool | detect (const sensor_msgs::PointCloud2ConstPtr &msg, int nModels, std::vector< std::string > &model_ids, std::vector< geometry_msgs::Pose > &poses, std::vector< float > &confidences, bool use_fitness_score=true) |
Given a cluster returns the n-most similar models in models_, their poses and the detection confidence. | |
bool | getVFHHistogramFromVFHId (pcl::PointCloud< pcl::VFHSignature308 > &vfh_descriptor, std::string vfh_id) |
bool | initialize (bool useDB, bf::path dpath, std::string root_dir, int linear=0) |
Initialize the data structures for recognition. | |
Private Types | |
typedef vfh_recognition::VFHRecognizer < Distance > | base_t |
typedef Distance< float > | DistT |
Private Member Functions | |
std::string | getModelId (std::string id) |
bool | getPointCloudFromId (pcl::PointCloud< pcl::PointNormal > &cloud, std::string id) |
bool | getPoseFromId (std::string id, geometry_msgs::Pose &pose) |
bool | getVFHCentroidFromVFHid (std::vector< float > ¢roid, std::string id) |
int | getVFHId (std::string id) |
bool | getVFHRollOrientationFromId (pcl::PointCloud< pcl::VFHSignature308 > &vfh_orientation_signature, std::string id) |
bool | getVFHRollOrientationFromIdThroughView (pcl::PointCloud< pcl::VFHSignature308 > &vfh_orientation_signature, std::string id) |
bool | getViewCentroidFromVFHid (std::vector< float > ¢roid, std::string id) |
Private Attributes | |
std::string | root_dir |
Definition at line 16 of file vfh_recognition.h.
typedef vfh_recognition::VFHRecognizer<Distance> vfh_recognizer_fs::VFHRecognizerFS< Distance >::base_t [private] |
Definition at line 19 of file vfh_recognition.h.
typedef Distance<float> vfh_recognizer_fs::VFHRecognizerFS< Distance >::DistT [private] |
Reimplemented from vfh_recognition::VFHRecognizer< Distance >.
Definition at line 24 of file vfh_recognition.h.
bool vfh_recognizer_fs::VFHRecognizerFS< Distance >::detect | ( | const sensor_msgs::PointCloud2ConstPtr & | msg, | |
int | nModels, | |||
std::vector< std::string > & | model_ids, | |||
std::vector< geometry_msgs::Pose > & | poses, | |||
std::vector< float > & | confidences, | |||
bool | use_fitness_score = true | |||
) | [inline] |
Given a cluster returns the n-most similar models in models_, their poses and the detection confidence.
Definition at line 234 of file vfh_recognition.cpp.
std::string vfh_recognizer_fs::VFHRecognizerFS< Distance >::getModelId | ( | std::string | id | ) | [inline, private, virtual] |
Implements vfh_recognition::VFHRecognizer< Distance >.
Definition at line 143 of file vfh_recognition.cpp.
bool vfh_recognizer_fs::VFHRecognizerFS< Distance >::getPointCloudFromId | ( | pcl::PointCloud< pcl::PointNormal > & | cloud, | |
std::string | id | |||
) | [inline, private, virtual] |
Implements vfh_recognition::VFHRecognizer< Distance >.
Definition at line 11 of file vfh_recognition.cpp.
bool vfh_recognizer_fs::VFHRecognizerFS< Distance >::getPoseFromId | ( | std::string | id, | |
geometry_msgs::Pose & | pose | |||
) | [inline, private, virtual] |
Implements vfh_recognition::VFHRecognizer< Distance >.
Definition at line 110 of file vfh_recognition.cpp.
bool vfh_recognizer_fs::VFHRecognizerFS< Distance >::getVFHCentroidFromVFHid | ( | std::vector< float > & | centroid, | |
std::string | id | |||
) | [inline, private, virtual] |
Implements vfh_recognition::VFHRecognizer< Distance >.
Definition at line 79 of file vfh_recognition.cpp.
bool vfh_recognizer_fs::VFHRecognizerFS< Distance >::getVFHHistogramFromVFHId | ( | pcl::PointCloud< pcl::VFHSignature308 > & | vfh_descriptor, | |
std::string | vfh_id | |||
) | [inline, virtual] |
Implements vfh_recognition::VFHRecognizer< Distance >.
Definition at line 46 of file vfh_recognition.cpp.
int vfh_recognizer_fs::VFHRecognizerFS< Distance >::getVFHId | ( | std::string | id | ) | [inline, private, virtual] |
Implements vfh_recognition::VFHRecognizer< Distance >.
Definition at line 151 of file vfh_recognition.cpp.
bool vfh_recognizer_fs::VFHRecognizerFS< Distance >::getVFHRollOrientationFromId | ( | pcl::PointCloud< pcl::VFHSignature308 > & | vfh_orientation_signature, | |
std::string | id | |||
) | [inline, private, virtual] |
Implements vfh_recognition::VFHRecognizer< Distance >.
Definition at line 58 of file vfh_recognition.cpp.
bool vfh_recognizer_fs::VFHRecognizerFS< Distance >::getVFHRollOrientationFromIdThroughView | ( | pcl::PointCloud< pcl::VFHSignature308 > & | vfh_orientation_signature, | |
std::string | id | |||
) | [inline, private, virtual] |
Implements vfh_recognition::VFHRecognizer< Distance >.
Definition at line 70 of file vfh_recognition.cpp.
bool vfh_recognizer_fs::VFHRecognizerFS< Distance >::getViewCentroidFromVFHid | ( | std::vector< float > & | centroid, | |
std::string | id | |||
) | [inline, private, virtual] |
Implements vfh_recognition::VFHRecognizer< Distance >.
Definition at line 103 of file vfh_recognition.cpp.
bool vfh_recognizer_fs::VFHRecognizerFS< Distance >::initialize | ( | bool | useDB, | |
bf::path | dpath, | |||
std::string | root_dir, | |||
int | linear = 0 | |||
) | [inline] |
Initialize the data structures for recognition.
useDB | - if true creates the structures from the database
|
Definition at line 167 of file vfh_recognition.cpp.
std::string vfh_recognizer_fs::VFHRecognizerFS< Distance >::root_dir [private] |
Definition at line 28 of file vfh_recognition.h.