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_FEATURES_SHOT_LRF_OMP_H_
00040 #define PCL_FEATURES_SHOT_LRF_OMP_H_
00041 
00042 #include <pcl/point_types.h>
00043 #include <pcl/features/feature.h>
00044 #include <pcl/features/shot_lrf.h>
00045 
00046 namespace pcl
00047 {
00065   template<typename PointInT, typename PointOutT = ReferenceFrame>
00066   class SHOTLocalReferenceFrameEstimationOMP : public SHOTLocalReferenceFrameEstimation<PointInT, PointOutT>
00067   {
00068     public:
00070     SHOTLocalReferenceFrameEstimationOMP ()
00071       {
00072         feature_name_ = "SHOTLocalReferenceFrameEstimationOMP";
00073         threads_ = 1;
00074       }
00075 
00079      inline void
00080      setNumberOfThreads (unsigned int nr_threads)
00081      {
00082        if (nr_threads == 0)
00083          nr_threads = 1;
00084        threads_ = nr_threads;
00085      }
00086 
00087     protected:
00088       using Feature<PointInT, PointOutT>::feature_name_;
00089       using Feature<PointInT, PointOutT>::getClassName;
00090       
00091       using Feature<PointInT, PointOutT>::input_;
00092       using Feature<PointInT, PointOutT>::indices_;
00093       using Feature<PointInT, PointOutT>::surface_;
00094       using Feature<PointInT, PointOutT>::tree_;
00095       using Feature<PointInT, PointOutT>::search_parameter_;
00096       using SHOTLocalReferenceFrameEstimation<PointInT, PointOutT>::getLocalRF;
00097       typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00098       typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00099 
00103       virtual void
00104       computeFeature (PointCloudOut &output);
00105 
00109       virtual void
00110       computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output);
00111 
00113       int threads_;
00114 
00115   };
00116 }
00117 
00118 #endif    // PCL_FEATURES_SHOT_LRF_H_
00119