Go to the documentation of this file.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 #ifndef PCL_FEATURES_SGFALL_H_
00039 #define PCL_FEATURES_SGFALL_H_
00040 
00041 #include <pcl17/features/feature.h>
00042 #include <pcl17/features/sgf1.h>
00043 #include <pcl17/features/sgf2.h>
00044 #include <pcl17/features/sgf3.h>
00045 #include <pcl17/features/sgf4.h>
00046 #include <pcl17/features/sgf5.h>
00047 #include <pcl17/features/sgf6.h>
00048 #include <pcl17/features/sgf7.h>
00049 #include <pcl17/features/sgf8.h>
00050 #include <pcl17/features/sgf9.h>
00051 
00052 #include <pcl17/features/esf.h>
00053 
00054 namespace pcl17
00055 {
00056 const int SGFALL_SIZE = 25;
00057 
00058 template<typename PointInT, typename PointOutT>
00059   class SGFALLEstimation : public Feature<PointInT, PointOutT>
00060   {
00061 
00062   public:
00063 
00064     using Feature<PointInT, PointOutT>::feature_name_;
00065     using Feature<PointInT, PointOutT>::input_;
00066     using Feature<PointInT, PointOutT>::surface_;
00067     using Feature<PointInT, PointOutT>::indices_;
00068     using Feature<PointInT, PointOutT>::search_parameter_;
00069     using Feature<PointInT, PointOutT>::tree_;
00070     using Feature<PointInT, PointOutT>::k_;
00071 
00072     typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00073     typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00074 
00076     SGFALLEstimation()
00077     {
00078       feature_name_ = "SGFALLEstimation";
00079       k_ = 1;
00080     }
00081     ;
00082 
00084     void computeFeature(PointCloudOut & sgfs)
00085     {
00086       size_t feature_counter = 0;
00087 
00088       sgfs.width = 1;
00089       sgfs.height = 1;
00090       sgfs.points.resize(1);
00091 
00093       
00094 
00095       pcl17::PointCloud<pcl17::Histogram<pcl17::SGF1_SIZE> >::Ptr
00096                                                             sgf1s(
00097                                                                   new pcl17::PointCloud<pcl17::Histogram<pcl17::SGF1_SIZE> >());
00098       pcl17::SGF1Estimation<PointInT, pcl17::Histogram<pcl17::SGF1_SIZE> > sgf1;
00099       sgf1.setInputCloud(input_);
00100       sgf1.setIndices(indices_);
00101       sgf1.setSearchMethod(tree_);
00102       sgf1.setKSearch(k_);
00103       sgf1.compute(*sgf1s);
00104 
00105       for (int n = 0; n < pcl17::SGF1_SIZE; ++n)
00106       {
00107         sgfs.points[0].histogram[feature_counter + n] = sgf1s->points[0].histogram[n];
00108       }
00109       feature_counter += pcl17::SGF1_SIZE;
00110 
00112       
00113 
00114       pcl17::PointCloud<pcl17::Histogram<pcl17::SGF2_SIZE> >::Ptr
00115                                                             sgf2s(
00116                                                                   new pcl17::PointCloud<pcl17::Histogram<pcl17::SGF2_SIZE> >());
00117       pcl17::SGF2Estimation<PointInT, pcl17::Histogram<pcl17::SGF2_SIZE> > sgf2;
00118       sgf2.setInputCloud(input_);
00119       sgf2.setIndices(indices_);
00120       sgf2.setKSearch(k_);
00121       sgf2.compute(*sgf2s);
00122 
00123       for (int n = 0; n < pcl17::SGF2_SIZE; ++n)
00124       {
00125         sgfs.points[0].histogram[feature_counter + n] = sgf2s->points[0].histogram[n];
00126       }
00127       feature_counter += pcl17::SGF2_SIZE;
00128 
00130       
00131 
00132       pcl17::PointCloud<pcl17::Histogram<pcl17::SGF3_SIZE> >::Ptr
00133                                                             sgf3s(
00134                                                                   new pcl17::PointCloud<pcl17::Histogram<pcl17::SGF3_SIZE> >());
00135       pcl17::SGF3Estimation<PointInT, pcl17::Histogram<pcl17::SGF3_SIZE> > sgf3;
00136       sgf3.setInputCloud(input_);
00137       sgf3.setIndices(indices_);
00138       sgf3.compute(*sgf3s);
00139 
00140       for (int n = 0; n < pcl17::SGF3_SIZE; ++n)
00141       {
00142         sgfs.points[0].histogram[feature_counter + n] = sgf3s->points[0].histogram[n];
00143       }
00144       feature_counter += pcl17::SGF3_SIZE;
00145 
00147       
00148 
00149       pcl17::PointCloud<pcl17::Histogram<pcl17::SGF4_SIZE> >::Ptr
00150                                                             sgf4s(
00151                                                                   new pcl17::PointCloud<pcl17::Histogram<pcl17::SGF4_SIZE> >());
00152       pcl17::SGF4Estimation<PointInT, pcl17::Histogram<pcl17::SGF4_SIZE> > sgf4;
00153       sgf4.setInputCloud(input_);
00154       sgf4.setIndices(indices_);
00155       sgf4.compute(*sgf4s);
00156 
00157       for (int n = 0; n < pcl17::SGF4_SIZE; ++n)
00158       {
00159         sgfs.points[0].histogram[feature_counter + n] = sgf4s->points[0].histogram[n];
00160       }
00161       feature_counter += pcl17::SGF4_SIZE;
00162 
00164       
00165 
00166       pcl17::PointCloud<pcl17::Histogram<pcl17::SGF5_SIZE> >::Ptr
00167                                                             sgf5s(
00168                                                                   new pcl17::PointCloud<pcl17::Histogram<pcl17::SGF5_SIZE> >());
00169       pcl17::SGF5Estimation<PointInT, pcl17::Histogram<pcl17::SGF5_SIZE> > sgf5;
00170       sgf5.setInputCloud(input_);
00171       sgf5.setIndices(indices_);
00172       sgf5.compute(*sgf5s);
00173 
00174       for (int n = 0; n < pcl17::SGF5_SIZE; ++n)
00175       {
00176         sgfs.points[0].histogram[feature_counter + n] = sgf5s->points[0].histogram[n];
00177       }
00178       feature_counter += pcl17::SGF5_SIZE;
00179 
00181       
00182 
00183       pcl17::PointCloud<pcl17::Histogram<pcl17::SGF6_SIZE> >::Ptr
00184                                                             sgf6s(
00185                                                                   new pcl17::PointCloud<pcl17::Histogram<pcl17::SGF6_SIZE> >());
00186       pcl17::SGF6Estimation<PointInT, pcl17::Histogram<pcl17::SGF6_SIZE> > sgf6;
00187       sgf6.setInputCloud(input_);
00188       sgf6.setIndices(indices_);
00189       sgf6.compute(*sgf6s);
00190 
00191       for (int n = 0; n < pcl17::SGF6_SIZE; ++n)
00192       {
00193         sgfs.points[0].histogram[feature_counter + n] = sgf6s->points[0].histogram[n];
00194       }
00195       feature_counter += pcl17::SGF6_SIZE;
00196 
00198       
00199 
00200       pcl17::PointCloud<pcl17::Histogram<pcl17::SGF7_SIZE> >::Ptr
00201                                                             sgf7s(
00202                                                                   new pcl17::PointCloud<pcl17::Histogram<pcl17::SGF7_SIZE> >());
00203       pcl17::SGF7Estimation<PointInT, pcl17::Histogram<pcl17::SGF7_SIZE> > sgf7;
00204       sgf7.setInputCloud(input_);
00205       sgf7.setIndices(indices_);
00206       sgf7.compute(*sgf7s);
00207 
00208       for (int n = 0; n < pcl17::SGF7_SIZE; ++n)
00209       {
00210         sgfs.points[0].histogram[feature_counter + n] = sgf7s->points[0].histogram[n];
00211       }
00212       feature_counter += pcl17::SGF7_SIZE;
00213 
00215       
00216 
00217       pcl17::PointCloud<pcl17::Histogram<pcl17::SGF8_SIZE> >::Ptr
00218                                                             sgf8s(
00219                                                                   new pcl17::PointCloud<pcl17::Histogram<pcl17::SGF8_SIZE> >());
00220       pcl17::SGF8Estimation<PointInT, pcl17::Histogram<pcl17::SGF8_SIZE> > sgf8;
00221       sgf8.setInputCloud(input_);
00222       sgf8.setIndices(indices_);
00223       sgf8.compute(*sgf8s);
00224 
00225       for (int n = 0; n < pcl17::SGF8_SIZE; ++n)
00226       {
00227         sgfs.points[0].histogram[feature_counter + n] = sgf8s->points[0].histogram[n];
00228       }
00229       feature_counter += pcl17::SGF8_SIZE;
00230 
00232       
00233 
00234       pcl17::PointCloud<pcl17::Histogram<pcl17::SGF9_SIZE> >::Ptr
00235                                                             sgf9s(
00236                                                                   new pcl17::PointCloud<pcl17::Histogram<pcl17::SGF9_SIZE> >());
00237       pcl17::SGF9Estimation<PointInT, pcl17::Histogram<pcl17::SGF9_SIZE> > sgf9;
00238       sgf9.setInputCloud(input_);
00239       sgf9.setIndices(indices_);
00240       sgf9.compute(*sgf9s);
00241 
00242       for (int n = 0; n < pcl17::SGF9_SIZE; ++n)
00243       {
00244         sgfs.points[0].histogram[feature_counter + n] = sgf9s->points[0].histogram[n];
00245       }
00246       feature_counter += pcl17::SGF9_SIZE;
00247 
00249       
00250 
00251 
00252 
00253 
00254 
00255 
00256 
00257 
00258 
00259 
00260 
00261 
00262 
00263 
00264 
00265     }
00267 
00268 
00269   private:
00270 
00274     void computeFeatureEigen(pcl17::PointCloud<Eigen::MatrixXf> &)
00275     {
00276     }
00277   };
00278 }
00279 
00280 #endif  //#ifndef PCL_FEATURES_SGF9_H_