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_PFHRGB_H_
00041 #define PCL_PFHRGB_H_
00042
00043 #include <pcl/features/feature.h>
00044 #include <pcl/features/pfh_tools.h>
00045
00046 namespace pcl
00047 {
00048 template <typename PointInT, typename PointNT, typename PointOutT = pcl::PFHRGBSignature250>
00049 class PFHRGBEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
00050 {
00051 public:
00052 typedef boost::shared_ptr<PFHRGBEstimation<PointInT, PointNT, PointOutT> > Ptr;
00053 typedef boost::shared_ptr<const PFHRGBEstimation<PointInT, PointNT, PointOutT> > ConstPtr;
00054 using PCLBase<PointInT>::indices_;
00055 using Feature<PointInT, PointOutT>::feature_name_;
00056 using Feature<PointInT, PointOutT>::surface_;
00057 using Feature<PointInT, PointOutT>::k_;
00058 using Feature<PointInT, PointOutT>::search_parameter_;
00059 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00060 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00061
00062
00063 PFHRGBEstimation ()
00064 : nr_subdiv_ (5), pfhrgb_histogram_ (), pfhrgb_tuple_ (), d_pi_ (1.0f / (2.0f * static_cast<float> (M_PI)))
00065 {
00066 feature_name_ = "PFHRGBEstimation";
00067 }
00068
00069 bool
00070 computeRGBPairFeatures (const pcl::PointCloud<PointInT> &cloud, const pcl::PointCloud<PointNT> &normals,
00071 int p_idx, int q_idx,
00072 float &f1, float &f2, float &f3, float &f4, float &f5, float &f6, float &f7);
00073
00074 void
00075 computePointPFHRGBSignature (const pcl::PointCloud<PointInT> &cloud, const pcl::PointCloud<PointNT> &normals,
00076 const std::vector<int> &indices, int nr_split, Eigen::VectorXf &pfhrgb_histogram);
00077
00078 protected:
00079 void
00080 computeFeature (PointCloudOut &output);
00081
00082 private:
00084 int nr_subdiv_;
00085
00087 Eigen::VectorXf pfhrgb_histogram_;
00088
00090 Eigen::VectorXf pfhrgb_tuple_;
00091
00093 int f_index_[7];
00094
00096 float d_pi_;
00097 };
00098 }
00099
00100 #ifdef PCL_NO_PRECOMPILE
00101 #include <pcl/features/impl/pfhrgb.hpp>
00102 #endif
00103
00104 #endif