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 #ifndef PCL_INTENSITY_GRADIENT_H_
00040 #define PCL_INTENSITY_GRADIENT_H_
00041
00042 #include <pcl/features/feature.h>
00043 #include <pcl/common/intensity.h>
00044
00045 namespace pcl
00046 {
00054 template <typename PointInT, typename PointNT, typename PointOutT, typename IntensitySelectorT = pcl::common::IntensityFieldAccessor<PointInT> >
00055 class IntensityGradientEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
00056 {
00057 public:
00058 using Feature<PointInT, PointOutT>::feature_name_;
00059 using Feature<PointInT, PointOutT>::getClassName;
00060 using Feature<PointInT, PointOutT>::indices_;
00061 using Feature<PointInT, PointOutT>::surface_;
00062 using Feature<PointInT, PointOutT>::k_;
00063 using Feature<PointInT, PointOutT>::search_parameter_;
00064 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00065
00066 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00067
00069 IntensityGradientEstimation ()
00070 {
00071 feature_name_ = "IntensityGradientEstimation";
00072 threads_ = 1;
00073 };
00074
00078 inline void
00079 setNumberOfThreads (int nr_threads)
00080 {
00081 threads_ = nr_threads == 0 ? 1 : nr_threads;
00082 }
00083
00084 protected:
00089 void
00090 computeFeature (PointCloudOut &output);
00091
00099 void
00100 computePointIntensityGradient (const pcl::PointCloud<PointInT> &cloud,
00101 const std::vector<int> &indices,
00102 const Eigen::Vector3f &point,
00103 float mean_intensity,
00104 const Eigen::Vector3f &normal,
00105 Eigen::Vector3f &gradient);
00106
00107 private:
00111 void
00112 computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &) {}
00113
00114 protected:
00116 IntensitySelectorT intensity_;
00118 int threads_;
00119 };
00120
00128 template <typename PointInT, typename PointNT>
00129 class IntensityGradientEstimation<PointInT, PointNT, Eigen::MatrixXf>: public IntensityGradientEstimation<PointInT, PointNT, pcl::IntensityGradient>
00130 {
00131 public:
00132 using IntensityGradientEstimation<PointInT, PointNT, pcl::IntensityGradient>::indices_;
00133 using IntensityGradientEstimation<PointInT, PointNT, pcl::IntensityGradient>::normals_;
00134 using IntensityGradientEstimation<PointInT, PointNT, pcl::IntensityGradient>::input_;
00135 using IntensityGradientEstimation<PointInT, PointNT, pcl::IntensityGradient>::surface_;
00136 using IntensityGradientEstimation<PointInT, PointNT, pcl::IntensityGradient>::k_;
00137 using IntensityGradientEstimation<PointInT, PointNT, pcl::IntensityGradient>::search_parameter_;
00138 using IntensityGradientEstimation<PointInT, PointNT, pcl::IntensityGradient>::compute;
00139
00140 protected:
00145 void
00146 computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output);
00147
00151 void
00152 compute (pcl::PointCloud<pcl::Normal> &) {}
00153 };
00154 }
00155
00156 #endif // #ifndef PCL_INTENSITY_GRADIENT_H_