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
00039
00040
00041 #ifndef PCL_PRINCIPAL_CURVATURES_H_
00042 #define PCL_PRINCIPAL_CURVATURES_H_
00043
00044 #include <pcl/features/eigen.h>
00045 #include <pcl/features/feature.h>
00046
00047 namespace pcl
00048 {
00060 template <typename PointInT, typename PointNT, typename PointOutT = pcl::PrincipalCurvatures>
00061 class PrincipalCurvaturesEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
00062 {
00063 public:
00064 typedef boost::shared_ptr<PrincipalCurvaturesEstimation<PointInT, PointNT, PointOutT> > Ptr;
00065 typedef boost::shared_ptr<const PrincipalCurvaturesEstimation<PointInT, PointNT, PointOutT> > ConstPtr;
00066 using Feature<PointInT, PointOutT>::feature_name_;
00067 using Feature<PointInT, PointOutT>::getClassName;
00068 using Feature<PointInT, PointOutT>::indices_;
00069 using Feature<PointInT, PointOutT>::k_;
00070 using Feature<PointInT, PointOutT>::search_parameter_;
00071 using Feature<PointInT, PointOutT>::surface_;
00072 using Feature<PointInT, PointOutT>::input_;
00073 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00074
00075 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00076 typedef pcl::PointCloud<PointInT> PointCloudIn;
00077
00079 PrincipalCurvaturesEstimation () :
00080 projected_normals_ (),
00081 xyz_centroid_ (Eigen::Vector3f::Zero ()),
00082 demean_ (Eigen::Vector3f::Zero ()),
00083 covariance_matrix_ (Eigen::Matrix3f::Zero ()),
00084 eigenvector_ (Eigen::Vector3f::Zero ()),
00085 eigenvalues_ (Eigen::Vector3f::Zero ())
00086 {
00087 feature_name_ = "PrincipalCurvaturesEstimation";
00088 };
00089
00102 void
00103 computePointPrincipalCurvatures (const pcl::PointCloud<PointNT> &normals,
00104 int p_idx, const std::vector<int> &indices,
00105 float &pcx, float &pcy, float &pcz, float &pc1, float &pc2);
00106
00107 protected:
00108
00114 void
00115 computeFeature (PointCloudOut &output);
00116
00117 private:
00119 std::vector<Eigen::Vector3f> projected_normals_;
00120
00122 Eigen::Vector3f xyz_centroid_;
00123
00125 Eigen::Vector3f demean_;
00126
00128 EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix_;
00129
00131 Eigen::Vector3f eigenvector_;
00133 Eigen::Vector3f eigenvalues_;
00134 };
00135 }
00136
00137 #ifdef PCL_NO_PRECOMPILE
00138 #include <pcl/features/impl/principal_curvatures.hpp>
00139 #endif
00140
00141 #endif //#ifndef PCL_PRINCIPAL_CURVATURES_H_