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_SHOT_OMP_H_
00041 #define PCL_SHOT_OMP_H_
00042
00043 #include <pcl/point_types.h>
00044 #include <pcl/features/feature.h>
00045 #include <pcl/features/shot.h>
00046
00047 namespace pcl
00048 {
00069 template <typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT352, typename PointRFT = pcl::ReferenceFrame>
00070 class SHOTEstimationOMP : public SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT>
00071 {
00072 public:
00073 typedef boost::shared_ptr<SHOTEstimationOMP<PointInT, PointNT, PointOutT, PointRFT> > Ptr;
00074 typedef boost::shared_ptr<const SHOTEstimationOMP<PointInT, PointNT, PointOutT, PointRFT> > ConstPtr;
00075 using Feature<PointInT, PointOutT>::feature_name_;
00076 using Feature<PointInT, PointOutT>::getClassName;
00077 using Feature<PointInT, PointOutT>::input_;
00078 using Feature<PointInT, PointOutT>::indices_;
00079 using Feature<PointInT, PointOutT>::k_;
00080 using Feature<PointInT, PointOutT>::search_parameter_;
00081 using Feature<PointInT, PointOutT>::search_radius_;
00082 using Feature<PointInT, PointOutT>::surface_;
00083 using Feature<PointInT, PointOutT>::fake_surface_;
00084 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00085 using FeatureWithLocalReferenceFrames<PointInT, PointRFT>::frames_;
00086 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::lrf_radius_;
00087 using SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT>::descLength_;
00088 using SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT>::nr_grid_sector_;
00089 using SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT>::nr_shape_bins_;
00090 using SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT>::sqradius_;
00091 using SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT>::radius3_4_;
00092 using SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT>::radius1_4_;
00093 using SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT>::radius1_2_;
00094
00095 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00096 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00097
00099 SHOTEstimationOMP (unsigned int nr_threads = 0) : SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT> (), threads_ (nr_threads)
00100 { };
00104 inline void
00105 setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; }
00106
00107 protected:
00108
00114 void
00115 computeFeature (PointCloudOut &output);
00116
00118 bool
00119 initCompute ();
00120
00122 unsigned int threads_;
00123 };
00124
00145 template <typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
00146 class SHOTColorEstimationOMP : public SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>
00147 {
00148 public:
00149 typedef boost::shared_ptr<SHOTColorEstimationOMP<PointInT, PointNT, PointOutT, PointRFT> > Ptr;
00150 typedef boost::shared_ptr<const SHOTColorEstimationOMP<PointInT, PointNT, PointOutT, PointRFT> > ConstPtr;
00151 using Feature<PointInT, PointOutT>::feature_name_;
00152 using Feature<PointInT, PointOutT>::getClassName;
00153 using Feature<PointInT, PointOutT>::input_;
00154 using Feature<PointInT, PointOutT>::indices_;
00155 using Feature<PointInT, PointOutT>::k_;
00156 using Feature<PointInT, PointOutT>::search_parameter_;
00157 using Feature<PointInT, PointOutT>::search_radius_;
00158 using Feature<PointInT, PointOutT>::surface_;
00159 using Feature<PointInT, PointOutT>::fake_surface_;
00160 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00161 using FeatureWithLocalReferenceFrames<PointInT, PointRFT>::frames_;
00162 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::lrf_radius_;
00163 using SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::descLength_;
00164 using SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::nr_grid_sector_;
00165 using SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::nr_shape_bins_;
00166 using SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::sqradius_;
00167 using SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::radius3_4_;
00168 using SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::radius1_4_;
00169 using SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::radius1_2_;
00170 using SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::b_describe_shape_;
00171 using SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::b_describe_color_;
00172 using SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::nr_color_bins_;
00173
00174 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00175 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00176
00178 SHOTColorEstimationOMP (bool describe_shape = true,
00179 bool describe_color = true,
00180 unsigned int nr_threads = 0)
00181 : SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT> (describe_shape, describe_color), threads_ (nr_threads)
00182 {
00183 }
00184
00188 inline void
00189 setNumberOfThreads (unsigned int nr_threads = 0) { threads_ = nr_threads; }
00190
00191 protected:
00192
00198 void
00199 computeFeature (PointCloudOut &output);
00200
00202 bool
00203 initCompute ();
00204
00206 unsigned int threads_;
00207 };
00208
00209 }
00210
00211 #ifdef PCL_NO_PRECOMPILE
00212 #include <pcl/features/impl/shot_omp.hpp>
00213 #endif
00214
00215 #endif //#ifndef PCL_SHOT_OMP_H_