00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #ifndef NNCLASSIFICATION_H_
00041 #define NNCLASSIFICATION_H_
00042
00043 #include <cstdlib>
00044 #include <cfloat>
00045 #include <algorithm>
00046 #include <boost/foreach.hpp>
00047 #include <boost/shared_ptr.hpp>
00048 #include <pcl/kdtree/kdtree_flann.h>
00049
00050 namespace pcl
00051 {
00058 template <typename PointT>
00059 class NNClassification
00060 {
00061 private:
00062
00063 typename pcl::KdTree<PointT>::Ptr tree_;
00064
00066 std::vector<std::string> classes_;
00068 std::vector<int> labels_idx_;
00069
00070 public:
00071
00072 NNClassification () : tree_ (), classes_ (), labels_idx_ () {}
00073
00075 typedef std::pair<std::vector<std::string>, std::vector<float> > Result;
00076 typedef boost::shared_ptr<Result> ResultPtr;
00077
00078
00079
00083 void
00084 setTrainingFeatures (const typename pcl::PointCloud<PointT>::ConstPtr &features)
00085 {
00086
00087 typename pcl::CustomPointRepresentation<PointT>::Ptr cpr (new pcl::CustomPointRepresentation<PointT> (INT_MAX, 0));
00088 tree_.reset (new pcl::KdTreeFLANN<PointT>);
00089 tree_->setPointRepresentation (cpr);
00090 tree_->setInputCloud (features);
00091 }
00092
00097 void
00098 setTrainingLabelIndicesAndLUT (const std::vector<std::string> &classes, const std::vector<int> &labels_idx)
00099 {
00100
00101 classes_ = classes;
00102 labels_idx_ = labels_idx;
00103 }
00104
00111 void
00112 setTrainingLabels (const std::vector<std::string> &labels)
00113 {
00114
00115 classes_ = labels;
00116 std::sort (classes_.begin(), classes_.end());
00117 classes_.erase (std::unique (classes_.begin(), classes_.end()), classes_.end());
00118
00119
00120 std::map<std::string, int> label2idx;
00121 for (std::vector<std::string>::const_iterator it = classes_.begin (); it != classes_.end (); it++)
00122 label2idx[*it] = int (it - classes_.begin ());
00123
00124
00125 labels_idx_.reserve (labels.size ());
00126 BOOST_FOREACH (std::string s, labels)
00127 labels_idx_.push_back (label2idx[s]);
00128
00129
00130 }
00131
00137 bool
00138 loadTrainingFeatures(std::string file_name, std::string labels_file_name)
00139 {
00140 typename pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00141 if (pcl::io::loadPCDFile (file_name.c_str (), *cloud) != 0)
00142 return (false);
00143 std::vector<std::string> labels;
00144 std::ifstream f (labels_file_name.c_str ());
00145 std::string label;
00146 while (getline (f, label))
00147 if (label.size () > 0)
00148 labels.push_back(label);
00149 if (labels.size () != cloud->points.size ())
00150 return (false);
00151 setTrainingFeatures (cloud);
00152 setTrainingLabels (labels);
00153 return (true);
00154 }
00155
00161 bool
00162 saveTrainingFeatures (std::string file_name, std::string labels_file_name)
00163 {
00164 typename pcl::PointCloud<PointT>::ConstPtr training_features = tree_->getInputCloud ();
00165 if (labels_idx_.size () == training_features->points.size ())
00166 {
00167 if (pcl::io::savePCDFile (file_name.c_str (), *training_features) != 0)
00168 return (false);
00169 std::ofstream f (labels_file_name.c_str ());
00170 BOOST_FOREACH (int i, labels_idx_)
00171 f << classes_[i] << "\n";
00172 return (true);
00173 }
00174 return (false);
00175 }
00176
00184 ResultPtr
00185 classify (const PointT &p_q, double radius, float gaussian_param, int max_nn = INT_MAX)
00186 {
00187 std::vector<int> k_indices;
00188 std::vector<float> k_sqr_distances;
00189 getSimilarExemplars (p_q, radius, k_indices, k_sqr_distances, max_nn);
00190 return (getGaussianBestScores (gaussian_param, k_indices, k_sqr_distances));
00191 }
00192
00201 int
00202 getKNearestExemplars (const PointT &p_q, int k, std::vector<int> &k_indices, std::vector<float> &k_sqr_distances)
00203 {
00204 k_indices.resize (k);
00205 k_sqr_distances.resize (k);
00206 return (tree_->nearestKSearch (p_q, k, k_indices, k_sqr_distances));
00207 }
00208
00217 int
00218 getSimilarExemplars (const PointT &p_q, double radius, std::vector<int> &k_indices,
00219 std::vector<float> &k_sqr_distances, int max_nn = INT_MAX)
00220 {
00221 return (tree_->radiusSearch (p_q, radius, k_indices, k_sqr_distances, max_nn));
00222 }
00223
00229 boost::shared_ptr<std::vector<float> >
00230 getSmallestSquaredDistances (std::vector<int> &k_indices, std::vector<float> &k_sqr_distances)
00231 {
00232
00233 boost::shared_ptr<std::vector<float> > sqr_distances (new std::vector<float> (classes_.size (), FLT_MAX));
00234
00235
00236 for (std::vector<int>::const_iterator i = k_indices.begin (); i != k_indices.end (); ++i)
00237 if ((*sqr_distances)[labels_idx_[*i]] > k_sqr_distances[i - k_indices.begin ()])
00238 (*sqr_distances)[labels_idx_[*i]] = k_sqr_distances[i - k_indices.begin ()];
00239 return (sqr_distances);
00240 }
00241
00248 ResultPtr
00249 getLinearBestScores (std::vector<int> &k_indices, std::vector<float> &k_sqr_distances)
00250 {
00251
00252 boost::shared_ptr<std::vector<float> > sqr_distances = getSmallestSquaredDistances (k_indices, k_sqr_distances);
00253
00254
00255 double sum_dist = 0;
00256 boost::shared_ptr<std::pair<std::vector<std::string>, std::vector<float> > > result (new std::pair<std::vector<std::string>, std::vector<float> > ());
00257 result->first.reserve (classes_.size ());
00258 result->second.reserve (classes_.size ());
00259 for (std::vector<float>::const_iterator it = sqr_distances->begin (); it != sqr_distances->end (); ++it)
00260 if (*it != FLT_MAX)
00261 {
00262 result->first.push_back (classes_[it - sqr_distances->begin ()]);
00263 result->second.push_back (sqrt (*it));
00264 sum_dist += result->second.back ();
00265 }
00266 for (std::vector<float>::iterator it = result->second.begin (); it != result->second.end (); ++it)
00267 *it = 1 - *it/sum_dist;
00268
00269
00270 return (result);
00271 }
00272
00279 ResultPtr
00280 getGaussianBestScores (float gaussian_param, std::vector<int> &k_indices, std::vector<float> &k_sqr_distances)
00281 {
00282
00283 boost::shared_ptr<std::vector<float> > sqr_distances = getSmallestSquaredDistances (k_indices, k_sqr_distances);
00284
00285
00286 boost::shared_ptr<std::pair<std::vector<std::string>, std::vector<float> > > result (new std::pair<std::vector<std::string>, std::vector<float> > ());
00287 result->first.reserve (classes_.size ());
00288 result->second.reserve (classes_.size ());
00289 for (std::vector<float>::const_iterator it = sqr_distances->begin (); it != sqr_distances->end (); ++it)
00290 if (*it != FLT_MAX)
00291 {
00292 result->first.push_back (classes_[it - sqr_distances->begin ()]);
00293
00294 result->second.push_back (expf (-sqrtf (*it) / gaussian_param));
00295 }
00296
00297
00298 return (result);
00299 }
00300 };
00301 }
00302
00303 #endif