Utility class for nearest neighbor search based classification of VFH features. More...
#include <vfh_nn_classifier.h>
Public Types | |
typedef pcl::PointCloud < pcl::VFHSignature308 > | FeatureCloud |
typedef pcl::PointCloud < pcl::VFHSignature308 > ::ConstPtr | FeatureCloudConstPtr |
typedef pcl::PointCloud < pcl::VFHSignature308 >::Ptr | FeatureCloudPtr |
typedef NNClassification < pcl::VFHSignature308 > ::Result | Result |
typedef NNClassification < pcl::VFHSignature308 > ::ResultPtr | ResultPtr |
Public Member Functions | |
bool | addTrainingData (const sensor_msgs::PointCloud2 &training_data, std::string &label) |
Add the feature extracted from the cloud as a training example with the given labels. | |
bool | addTrainingFeatures (const FeatureCloudPtr training_features, const std::vector< std::string > &labels) |
Fill the list of training examples and corresponding labels. | |
ResultPtr | classify (const sensor_msgs::PointCloud2 &testing_data, double radius=300, double min_score=0.002) |
Utility function for the default classification process. | |
FeatureCloudPtr | computeFeature (const sensor_msgs::PointCloud2 &points, double radius=0.03) |
Extract the VFH feature describing the given point cloud. | |
void | finalizeLabels () |
Set up the classifier with the current training example labels. | |
void | finalizeTraining () |
Set up the classifier with the current training features and labels. | |
void | finalizeTree () |
Set up the classifier with the current training features. | |
bool | loadTrainingData (std::string file_name, std::string label) |
Add the feature extracted from the cloud at the specified location as a training example with the given labels. | |
bool | loadTrainingFeatures (std::string file_name, std::string labels_file_name) |
Fill the list of training examples and corresponding labels. | |
void | reset () |
bool | saveTrainingFeatures (std::string file_name, std::string labels_file_name) |
Save the list of training examples and corresponding labels. | |
VFHClassifierNN () | |
Private Attributes | |
NNClassification < pcl::VFHSignature308 > | classifier_ |
Nearest neighbor classifier instantiated for VFH features. | |
std::vector< std::string > | labels_ |
Class label for each training example. | |
FeatureCloudPtr | training_features_ |
Point cloud containing the training VFH features. |
Utility class for nearest neighbor search based classification of VFH features.
Definition at line 93 of file vfh_nn_classifier.h.
Definition at line 97 of file vfh_nn_classifier.h.
typedef pcl::PointCloud<pcl::VFHSignature308>::ConstPtr pcl::VFHClassifierNN::FeatureCloudConstPtr |
Definition at line 99 of file vfh_nn_classifier.h.
Definition at line 98 of file vfh_nn_classifier.h.
Definition at line 100 of file vfh_nn_classifier.h.
Definition at line 101 of file vfh_nn_classifier.h.
pcl::VFHClassifierNN::VFHClassifierNN | ( | ) | [inline] |
Definition at line 114 of file vfh_nn_classifier.h.
bool pcl::VFHClassifierNN::addTrainingData | ( | const sensor_msgs::PointCloud2 & | training_data, |
std::string & | label | ||
) | [inline] |
Add the feature extracted from the cloud as a training example with the given labels.
training_data | point cloud for training feature extraction |
label | the class label for the training example |
Definition at line 228 of file vfh_nn_classifier.h.
bool pcl::VFHClassifierNN::addTrainingFeatures | ( | const FeatureCloudPtr | training_features, |
const std::vector< std::string > & | labels | ||
) | [inline] |
Fill the list of training examples and corresponding labels.
training_features | the training features |
labels | the class label for each training example |
Definition at line 170 of file vfh_nn_classifier.h.
ResultPtr pcl::VFHClassifierNN::classify | ( | const sensor_msgs::PointCloud2 & | testing_data, |
double | radius = 300 , |
||
double | min_score = 0.002 |
||
) | [inline] |
Utility function for the default classification process.
testing_data | the point clouds to be classified |
radius | the maximum search radius in feature space -- 300 by default |
minimum_score | the score to be given to matches at maximum distance (>0) -- 0.002 by default |
Definition at line 245 of file vfh_nn_classifier.h.
FeatureCloudPtr pcl::VFHClassifierNN::computeFeature | ( | const sensor_msgs::PointCloud2 & | points, |
double | radius = 0.03 |
||
) | [inline] |
Extract the VFH feature describing the given point cloud.
points | point cloud for feature extraction |
radius | search radius for normal estimation -- 0.03 m by default |
Definition at line 260 of file vfh_nn_classifier.h.
void pcl::VFHClassifierNN::finalizeLabels | ( | ) | [inline] |
Set up the classifier with the current training example labels.
Definition at line 140 of file vfh_nn_classifier.h.
void pcl::VFHClassifierNN::finalizeTraining | ( | ) | [inline] |
Set up the classifier with the current training features and labels.
Definition at line 127 of file vfh_nn_classifier.h.
void pcl::VFHClassifierNN::finalizeTree | ( | ) | [inline] |
Set up the classifier with the current training features.
Definition at line 134 of file vfh_nn_classifier.h.
bool pcl::VFHClassifierNN::loadTrainingData | ( | std::string | file_name, |
std::string | label | ||
) | [inline] |
Add the feature extracted from the cloud at the specified location as a training example with the given labels.
file_name | PCD file containing the training data |
label | the class label for the training example |
Definition at line 214 of file vfh_nn_classifier.h.
bool pcl::VFHClassifierNN::loadTrainingFeatures | ( | std::string | file_name, |
std::string | labels_file_name | ||
) | [inline] |
Fill the list of training examples and corresponding labels.
file_name | PCD file containing the training features |
labels_file_name | the class label for each training example |
Definition at line 193 of file vfh_nn_classifier.h.
void pcl::VFHClassifierNN::reset | ( | ) | [inline] |
Definition at line 119 of file vfh_nn_classifier.h.
bool pcl::VFHClassifierNN::saveTrainingFeatures | ( | std::string | file_name, |
std::string | labels_file_name | ||
) | [inline] |
Save the list of training examples and corresponding labels.
file_name | file name for writing the training features |
labels_file_name | file name for writing the class label for each training example |
Definition at line 150 of file vfh_nn_classifier.h.
Nearest neighbor classifier instantiated for VFH features.
Definition at line 110 of file vfh_nn_classifier.h.
std::vector<std::string> pcl::VFHClassifierNN::labels_ [private] |
Class label for each training example.
Definition at line 108 of file vfh_nn_classifier.h.
Point cloud containing the training VFH features.
Definition at line 106 of file vfh_nn_classifier.h.