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_SGF3_H_
00039 #define PCL_FEATURES_SGF3_H_
00040
00041 #include <pcl17/features/feature.h>
00042 #include <pcl17/filters/voxel_grid.h>
00043
00044 namespace pcl17 {
00045 const int SGF3_SIZE = 1;
00046
00047 template<typename PointInT, typename PointOutT>
00048 class SGF3Estimation: public Feature<PointInT, PointOutT> {
00049
00050 public:
00051
00052 using Feature<PointInT, PointOutT>::feature_name_;
00053 using Feature<PointInT, PointOutT>::input_;
00054 using Feature<PointInT, PointOutT>::indices_;
00055 using Feature<PointInT, PointOutT>::k_;
00056
00057 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00058 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00059
00061 SGF3Estimation() {
00062 feature_name_ = "SGF3Estimation";
00063 k_ = 1;
00064 grid_size_ = 0.01f;
00065 }
00066 ;
00067
00068 void setGridSize(float grid_size) {
00069 grid_size_ = grid_size;
00070 }
00071
00072 float setGridSize() {
00073 return grid_size_;
00074 }
00075
00077 void computeFeature(PointCloudOut &output) {
00078
00079
00080 typename PointCloud<PointInT>::Ptr cloud(new PointCloud<PointInT> ());
00081 cloud->width = indices_->size();
00082 cloud->height = 1;
00083 cloud->points.resize(cloud->width * cloud->height);
00084 for (size_t idx = 0; idx < indices_->size(); ++idx) {
00085 cloud->points[idx] = input_->points[(*indices_)[idx]];
00086 }
00087
00088 typename PointCloud<PointInT>::Ptr cloud_filtered(new PointCloud<
00089 PointInT> ());
00090
00091
00092 pcl17::VoxelGrid<PointInT> sor;
00093 sor.setInputCloud(cloud);
00094 sor.setLeafSize(grid_size_, grid_size_, grid_size_);
00095 sor.filter(*cloud_filtered);
00096
00097
00098 int nr_points = cloud_filtered->width * cloud_filtered->height;
00099 output.points[0].histogram[0] = nr_points * grid_size_ * grid_size_
00100 * grid_size_;
00101 }
00103
00104
00105 private:
00106
00107 float grid_size_;
00108
00110 Eigen::VectorXf sgf_histogram_;
00111
00115 void computeFeatureEigen(pcl17::PointCloud<Eigen::MatrixXf> &) {
00116 }
00117 };
00118 }
00119
00120 #endif //#ifndef PCL_FEATURES_SGF3_H_