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 #ifndef PCL_INTENSITY_GRADIENT_H_
00041 #define PCL_INTENSITY_GRADIENT_H_
00042
00043 #include <pcl/features/feature.h>
00044 #include <pcl/common/intensity.h>
00045
00046 namespace pcl
00047 {
00055 template <typename PointInT, typename PointNT, typename PointOutT, typename IntensitySelectorT = pcl::common::IntensityFieldAccessor<PointInT> >
00056 class IntensityGradientEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
00057 {
00058 public:
00059 typedef boost::shared_ptr<IntensityGradientEstimation<PointInT, PointNT, PointOutT, IntensitySelectorT> > Ptr;
00060 typedef boost::shared_ptr<const IntensityGradientEstimation<PointInT, PointNT, PointOutT, IntensitySelectorT> > ConstPtr;
00061 using Feature<PointInT, PointOutT>::feature_name_;
00062 using Feature<PointInT, PointOutT>::getClassName;
00063 using Feature<PointInT, PointOutT>::indices_;
00064 using Feature<PointInT, PointOutT>::surface_;
00065 using Feature<PointInT, PointOutT>::k_;
00066 using Feature<PointInT, PointOutT>::search_parameter_;
00067 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00068
00069 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00070
00072 IntensityGradientEstimation () : intensity_ (), threads_ (0)
00073 {
00074 feature_name_ = "IntensityGradientEstimation";
00075 };
00076
00080 inline void
00081 setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; }
00082
00083 protected:
00088 void
00089 computeFeature (PointCloudOut &output);
00090
00098 void
00099 computePointIntensityGradient (const pcl::PointCloud<PointInT> &cloud,
00100 const std::vector<int> &indices,
00101 const Eigen::Vector3f &point,
00102 float mean_intensity,
00103 const Eigen::Vector3f &normal,
00104 Eigen::Vector3f &gradient);
00105
00106 protected:
00108 IntensitySelectorT intensity_;
00110 unsigned int threads_;
00111 };
00112 }
00113
00114 #ifdef PCL_NO_PRECOMPILE
00115 #include <pcl/features/impl/intensity_gradient.hpp>
00116 #endif
00117
00118 #endif // #ifndef PCL_INTENSITY_GRADIENT_H_