knn_classifier.cpp
Go to the documentation of this file.
00001 
00063 /*
00064  * knn_classifier.cpp
00065  *
00066  *  Created on: 04.10.2011
00067  *      Author: goa-sf
00068  */
00069 
00070 #include <fstream>
00071 #include <boost/foreach.hpp>
00072 
00073 #include <cob_3d_features/knn_classifier.h>
00074 
00075 #include <flann/algorithms/dist.h>
00076 #include <pcl/io/pcd_io.h>
00077 
00078 using namespace std;
00079 using namespace cob_3d_features;
00080 
00081 template<typename PointT>
00082 KNNClassifier<PointT>::KNNClassifier() :
00083   k_(1)
00084 { }
00085 
00086 template<typename PointT>
00087 KNNClassifier<PointT>::~KNNClassifier()
00088 { }
00089 
00090 /*********************************************************************
00091  *
00092  * !! The following only works with a modified PCL !!
00093  * New instantiations of the KdTreeFLANN class are needed.
00094  *
00095  *********************************************************************/
00096 /*
00097 template<typename PointT> void
00098 KNNClassifier<PointT>::setTrainingFeatures(const PointCloudPtr &features, string &distanceMetric)
00099 {
00100   //pcl::KdTreeFLANN<PointT, flann::L1<float> > tree;
00101   typename pcl::CustomPointRepresentation<PointT>::Ptr cpr (new pcl::CustomPointRepresentation<PointT> (INT_MAX, 0));
00102   if(distanceMetric == "L2")
00103   {
00104     tree_.reset(new pcl::KdTreeFLANN<PointT, flann::L2_Simple<float> >());
00105     distanceMetric_ = distanceMetric;
00106   }
00107   else if (distanceMetric == "L1")
00108   {
00109     tree_.reset(new pcl::KdTreeFLANN<PointT, flann::L1<float> >());
00110     distanceMetric_ = distanceMetric;
00111   }
00112   else if (distanceMetric == "HIK")
00113   {
00114     tree_.reset(new pcl::KdTreeFLANN<PointT, flann::HistIntersectionDistance<float> >());
00115     distanceMetric_ = distanceMetric;
00116   }
00117   else if (distanceMetric == "ChiSquare")
00118   {
00119     tree_.reset(new pcl::KdTreeFLANN<PointT, flann::ChiSquareDistance<float> >());
00120     distanceMetric_ = distanceMetric;
00121   }
00122   else if (distanceMetric == "Hellinger")
00123   {
00124     tree_.reset(new pcl::KdTreeFLANN<PointT, flann::HellingerDistance<float> >());
00125     distanceMetric_ = distanceMetric;
00126   }
00127   else
00128   {
00129     cout << "[KNNClassifier::setTrainingFeatures()]: \"" << distanceMetric << "\" not supported!\n";
00130     cout << "Selected default: L2" << endl;
00131     tree_.reset(new pcl::KdTreeFLANN<PointT>);
00132     distanceMetric_ = "L2";
00133   }
00134   tree_->setPointRepresentation(cpr);
00135   tree_->setInputCloud(features);
00136 }
00137 */
00138 
00139 /*********************************************************************
00140  *
00141  * Use the following for an unmodified version of PCL
00142  *
00143  *********************************************************************/
00144 
00145 template<typename PointT> void
00146 KNNClassifier<PointT>::setTrainingFeatures(const PointCloudPtr &features, string &distanceMetric)
00147 {
00148   typename pcl::CustomPointRepresentation<PointT>::Ptr cpr (new pcl::CustomPointRepresentation<PointT> (INT_MAX, 0));
00149   tree_.reset(new pcl::KdTreeFLANN<PointT>);
00150   distanceMetric_ = "L2";
00151   tree_->setPointRepresentation(cpr);
00152   tree_->setInputCloud(features);
00153 }
00154 
00155 template<typename PointT> void
00156 KNNClassifier<PointT>::setTrainingLabels(const vector<int> &labels)
00157 {
00158   labels_ = labels;
00159   labels_max_ = 7;//*max_element(labels_.begin(), labels_.end());
00160 }
00161 
00162 template<typename PointT> void
00163 KNNClassifier<PointT>::setKNeighbors(int k)
00164 {
00165   k_ = k;
00166 }
00167 
00168 template<typename PointT> int
00169 KNNClassifier<PointT>::saveTrainingData(string &features_file_name, string &labels_file_name)
00170 {
00171   PointCloudConstPtr training_features = tree_->getInputCloud();
00172   if (labels_.size() == training_features->size())
00173   {
00174     if (int res = pcl::io::savePCDFile(features_file_name.c_str(), *training_features) == -1)
00175       return res;
00176     ofstream f (labels_file_name.c_str());
00177     f << distanceMetric_ << endl;
00178     BOOST_FOREACH (int i, labels_)
00179       f << i << endl;
00180     return 0;
00181   }
00182   return -1;
00183 }
00184 
00185 template<typename PointT> int
00186 KNNClassifier<PointT>::loadTrainingData(string &features_file_name, string &labels_file_name)
00187 {
00188   PointCloudPtr cloud(new pcl::PointCloud<PointT>);
00189   if (int res = pcl::io::loadPCDFile(features_file_name.c_str(), *cloud) == -1)
00190     return res;
00191   vector<int> labels;
00192   ifstream f (labels_file_name.c_str());
00193   string line, metric;
00194   getline(f, metric);
00195 
00196   while(getline(f, line))
00197   {
00198     if (line.size() > 0)
00199       labels.push_back(atoi(line.c_str()));
00200   }
00201   if (labels.size() != cloud->size())
00202     return -1;
00203   setTrainingLabels(labels);
00204   setTrainingFeatures(cloud, metric);
00205   return 0;
00206 }
00207 
00208 template<typename PointT> int
00209 KNNClassifier<PointT>::classify(const PointT &p_q)
00210 {
00211   vector<int> label_counter(labels_max_, 0);
00212   vector<int> k_indices;
00213   vector<float> k_distances;
00214   tree_->nearestKSearch(p_q, k_, k_indices, k_distances);
00215   BOOST_FOREACH (int i, k_indices)
00216     label_counter[labels_[i]]++;
00217 //  int max_idx = *max_element(label_counter.begin(), label_counter.end());
00218   int max_label_counter = 0;
00219   for (int i=0; i<labels_max_; ++i)
00220     max_label_counter = max(label_counter[i], max_label_counter);
00221   for (int i=0; i<labels_max_; ++i)
00222   {
00223     if(label_counter[i] == max_label_counter)
00224       return i;
00225   }
00226   return (-1);
00227 }
00228 
00229 template class KNNClassifier<pcl::PointXYZ>;
00230 template class KNNClassifier<pcl::PointXYZRGBA>;
00231 template class KNNClassifier<pcl::FPFHSignature33>;


cob_3d_features
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:02:26