Go to the documentation of this file.00001 #ifndef PCL_PPFRGB_H_
00002 #define PCL_PPFRGB_H_
00003
00004 #include <pcl/features/feature.h>
00005 #include <boost/unordered_map.hpp>
00006
00007 namespace pcl
00008 {
00009 template <typename PointInT, typename PointNT, typename PointOutT>
00010 class PPFRGBEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
00011 {
00012 public:
00013 using PCLBase<PointInT>::indices_;
00014 using Feature<PointInT, PointOutT>::input_;
00015 using Feature<PointInT, PointOutT>::feature_name_;
00016 using Feature<PointInT, PointOutT>::getClassName;
00017 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00018
00019 typedef pcl::PointCloud<PointOutT> PointCloudOut;
00020
00024 PPFRGBEstimation ();
00025
00026
00027 private:
00031 void
00032 computeFeature (PointCloudOut &output);
00033
00037 void
00038 computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &) {}
00039 };
00040
00041 template <typename PointInT, typename PointNT, typename PointOutT>
00042 class PPFRGBRegionEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
00043 {
00044 public:
00045 using PCLBase<PointInT>::indices_;
00046 using Feature<PointInT, PointOutT>::input_;
00047 using Feature<PointInT, PointOutT>::feature_name_;
00048 using Feature<PointInT, PointOutT>::search_radius_;
00049 using Feature<PointInT, PointOutT>::tree_;
00050 using Feature<PointInT, PointOutT>::getClassName;
00051 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00052
00053 typedef pcl::PointCloud<PointOutT> PointCloudOut;
00054
00055 PPFRGBRegionEstimation ();
00056
00057 private:
00058 void
00059 computeFeature (PointCloudOut &output);
00060
00064 void
00065 computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &) {}
00066 };
00067 }
00068
00069 #endif // PCL_PPFRGB_H_