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_SGF9_H_
00039 #define PCL_FEATURES_SGF9_H_
00040
00041 #include <pcl17/features/feature.h>
00042 #include <pcl17/features/sgf3.h>
00043
00044 namespace pcl17
00045 {
00046 const int SGF9_SIZE = 1;
00047
00048 template <typename PointInT, typename PointOutT>
00049 class SGF9Estimation : public Feature<PointInT, PointOutT>
00050 {
00051
00052 public:
00053
00054 using Feature<PointInT, PointOutT>::feature_name_;
00055 using Feature<PointInT, PointOutT>::input_;
00056 using Feature<PointInT, PointOutT>::surface_;
00057 using Feature<PointInT, PointOutT>::indices_;
00058 using Feature<PointInT, PointOutT>::search_parameter_;
00059 using Feature<PointInT, PointOutT>::tree_;
00060 using Feature<PointInT, PointOutT>::k_;
00061
00062 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00063 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00064
00066 SGF9Estimation ()
00067 {
00068 feature_name_ = "SGF9Estimation";
00069 k_ = 1;
00070 };
00071
00072
00074 void
00075 computeFeature (PointCloudOut &output)
00076 {
00077
00078 typename PointCloud<PointInT>::Ptr cloud (new PointCloud<PointInT> ());
00079 cloud->width = indices_->size ();
00080 cloud->height = 1;
00081 cloud->points.resize (cloud->width * cloud->height);
00082 for (size_t idx = 0; idx < indices_->size (); ++idx)
00083 {
00084 cloud->points[idx] = input_->points[(*indices_)[idx]];
00085 }
00086
00087
00088
00089 const int sgf3_size = 1;
00090 pcl17::PointCloud<pcl17::Histogram<sgf3_size> >::Ptr sgf3s (new pcl17::PointCloud<pcl17::Histogram<sgf3_size> > ());
00091 pcl17::SGF3Estimation<PointInT, pcl17::Histogram<sgf3_size> > sgf3;
00092 sgf3.setInputCloud (cloud);
00093 sgf3.compute (*sgf3s);
00094
00095
00096
00097 EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
00098 Eigen::Vector4f centroid3;
00099 compute3DCentroid (*cloud, centroid3);
00100 computeCovarianceMatrix (*cloud, centroid3, covariance_matrix);
00101 EIGEN_ALIGN16 Eigen::Vector3f eigen_values;
00102 EIGEN_ALIGN16 Eigen::Matrix3f eigen_vectors;
00103 pcl17::eigen33 (covariance_matrix, eigen_vectors, eigen_values);
00104
00105
00106
00107 float box_vol = 8 * eigen_values[0] * eigen_values[1] * eigen_values[2];
00108
00109
00110
00111 output.points[0].histogram[0] = box_vol != 0 ? sgf3s->points[0].histogram[0] / box_vol : 0;
00112 }
00114
00115
00116 private:
00117
00121 void
00122 computeFeatureEigen (pcl17::PointCloud<Eigen::MatrixXf> &) {}
00123 };
00124 }
00125
00126 #endif //#ifndef PCL_FEATURES_SGF9_H_