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_SGF6_H_
00039 #define PCL_FEATURES_SGF6_H_
00040
00041 #include <pcl17/features/feature.h>
00042
00043 namespace pcl17
00044 {
00045 const int SGF6_SIZE = 2;
00046
00047 template <typename PointInT, typename PointOutT>
00048 class SGF6Estimation : public Feature<PointInT, PointOutT>
00049 {
00050
00051 public:
00052
00053 using Feature<PointInT, PointOutT>::feature_name_;
00054 using Feature<PointInT, PointOutT>::input_;
00055 using Feature<PointInT, PointOutT>::indices_;
00056 using Feature<PointInT, PointOutT>::k_;
00057
00058 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00059 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00060
00062 SGF6Estimation ()
00063 {
00064 feature_name_ = "SGF6Estimation";
00065 k_ = 1;
00066 axis1_ << 0, 0, 1;
00067 axis2_ << 1, 0, 0;
00068 };
00069
00070 void
00071 setAxis1(Eigen::Vector3f axis)
00072 {
00073 axis1_[0] = axis[0];
00074 axis1_[1] = axis[1];
00075 axis1_[2] = axis[2];
00076 }
00077
00078 void
00079 setAxis2(Eigen::Vector3f axis)
00080 {
00081 axis2_[0] = axis[0];
00082 axis2_[1] = axis[1];
00083 axis2_[2] = axis[2];
00084 }
00085
00086
00088 void
00089 computeFeature (PointCloudOut &output)
00090 {
00091
00092 typename PointCloud<PointInT>::Ptr cloud (new PointCloud<PointInT> ());
00093 cloud->width = indices_->size ();
00094 cloud->height = 1;
00095 cloud->points.resize (cloud->width * cloud->height);
00096 for (size_t idx = 0; idx < indices_->size (); ++idx)
00097 {
00098 cloud->points[idx] = input_->points[(*indices_)[idx]];
00099 }
00100
00101
00102
00103 EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
00104 Eigen::Vector4f centroid3;
00105 compute3DCentroid (*cloud, centroid3);
00106 computeCovarianceMatrix (*cloud, centroid3, covariance_matrix);
00107 EIGEN_ALIGN16 Eigen::Vector3f eigen_values;
00108 EIGEN_ALIGN16 Eigen::Matrix3f eigen_vectors;
00109 pcl17::eigen33 (covariance_matrix, eigen_vectors, eigen_values);
00110
00111
00112
00113 Eigen::Vector3f e (eigen_vectors (0, 0), eigen_vectors (1, 0), eigen_vectors (2, 0));
00114
00115
00116
00117 output.points[0].histogram[0] = acos (e.dot(axis1_) / axis1_.norm ());
00118 output.points[0].histogram[1] = acos (e.dot(axis2_) / axis1_.norm ());
00119 }
00121
00122
00123 private:
00124
00125 Eigen::Vector3f axis1_;
00126 Eigen::Vector3f axis2_;
00127
00131 void
00132 computeFeatureEigen (pcl17::PointCloud<Eigen::MatrixXf> &) {}
00133 };
00134 }
00135
00136 #endif //#ifndef PCL_FEATURES_SGF6_H_