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 #ifndef PCL_SHOT_OMP_H_
00038 #define PCL_SHOT_OMP_H_
00039
00040 #include <pcl/point_types.h>
00041 #include <pcl/features/feature.h>
00042 #include <pcl/features/shot.h>
00043
00044 namespace pcl
00045 {
00064 template <typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT352, typename PointRFT = pcl::ReferenceFrame>
00065 class SHOTEstimationOMP : public SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT>
00066 {
00067 public:
00068 using Feature<PointInT, PointOutT>::feature_name_;
00069 using Feature<PointInT, PointOutT>::getClassName;
00070 using Feature<PointInT, PointOutT>::input_;
00071 using Feature<PointInT, PointOutT>::indices_;
00072 using Feature<PointInT, PointOutT>::k_;
00073 using Feature<PointInT, PointOutT>::search_parameter_;
00074 using Feature<PointInT, PointOutT>::search_radius_;
00075 using Feature<PointInT, PointOutT>::surface_;
00076 using Feature<PointInT, PointOutT>::fake_surface_;
00077 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00078 using FeatureWithLocalReferenceFrames<PointInT, PointRFT>::frames_;
00079 using SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT>::descLength_;
00080 using SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT>::nr_grid_sector_;
00081 using SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT>::nr_shape_bins_;
00082 using SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT>::sqradius_;
00083 using SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT>::radius3_4_;
00084 using SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT>::radius1_4_;
00085 using SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT>::radius1_2_;
00086
00087 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00088 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00089
00091 SHOTEstimationOMP (unsigned int nr_threads = - 1) : SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT> (), threads_ ()
00092 {
00093 setNumberOfThreads (nr_threads);
00094 }
00095
00099 inline void
00100 setNumberOfThreads (unsigned int nr_threads)
00101 {
00102 if (nr_threads == 0)
00103 nr_threads = 1;
00104 threads_ = nr_threads;
00105 }
00106
00107 protected:
00108
00114 void
00115 computeFeature (PointCloudOut &output);
00116
00118 bool
00119 initCompute ();
00120
00122 int threads_;
00123 };
00124
00125 template <typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
00126 class SHOTColorEstimationOMP : public SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>
00127 {
00128 public:
00129 using Feature<PointInT, PointOutT>::feature_name_;
00130 using Feature<PointInT, PointOutT>::getClassName;
00131 using Feature<PointInT, PointOutT>::input_;
00132 using Feature<PointInT, PointOutT>::indices_;
00133 using Feature<PointInT, PointOutT>::k_;
00134 using Feature<PointInT, PointOutT>::search_parameter_;
00135 using Feature<PointInT, PointOutT>::search_radius_;
00136 using Feature<PointInT, PointOutT>::surface_;
00137 using Feature<PointInT, PointOutT>::fake_surface_;
00138 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00139 using FeatureWithLocalReferenceFrames<PointInT, PointRFT>::frames_;
00140 using SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::descLength_;
00141 using SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::nr_grid_sector_;
00142 using SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::nr_shape_bins_;
00143 using SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::sqradius_;
00144 using SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::radius3_4_;
00145 using SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::radius1_4_;
00146 using SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::radius1_2_;
00147 using SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::b_describe_shape_;
00148 using SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::b_describe_color_;
00149 using SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT>::nr_color_bins_;
00150
00151 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00152 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00153
00155 SHOTColorEstimationOMP (bool describe_shape = true,
00156 bool describe_color = true,
00157 unsigned int nr_threads = - 1)
00158 : SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT> (describe_shape, describe_color), threads_ ()
00159 {
00160 setNumberOfThreads (nr_threads);
00161 }
00162
00166 inline void
00167 setNumberOfThreads (unsigned int nr_threads)
00168 {
00169 if (nr_threads == 0)
00170 nr_threads = 1;
00171 threads_ = nr_threads;
00172 }
00173
00174 protected:
00175
00181 void
00182 computeFeature (PointCloudOut &output);
00183
00185 bool
00186 initCompute ();
00187
00189 int threads_;
00190 };
00191
00192 template <typename PointInT, typename PointNT, typename PointRFT>
00193 class PCL_DEPRECATED_CLASS (SHOTEstimationOMP, "SHOTEstimationOMP<..., pcl::SHOT, ...> IS DEPRECATED, USE SHOTEstimationOMP<..., pcl::SHOT352, ...> INSTEAD")
00194 <PointInT, PointNT, pcl::SHOT, PointRFT>
00195 : public SHOTEstimation<PointInT, PointNT, pcl::SHOT, PointRFT>
00196 {
00197 public:
00198 using Feature<PointInT, pcl::SHOT>::feature_name_;
00199 using Feature<PointInT, pcl::SHOT>::getClassName;
00200 using Feature<PointInT, pcl::SHOT>::input_;
00201 using Feature<PointInT, pcl::SHOT>::indices_;
00202 using Feature<PointInT, pcl::SHOT>::k_;
00203 using Feature<PointInT, pcl::SHOT>::search_parameter_;
00204 using Feature<PointInT, pcl::SHOT>::search_radius_;
00205 using Feature<PointInT, pcl::SHOT>::surface_;
00206 using Feature<PointInT, pcl::SHOT>::fake_surface_;
00207 using FeatureFromNormals<PointInT, PointNT, pcl::SHOT>::normals_;
00208 using FeatureWithLocalReferenceFrames<PointInT, PointRFT>::frames_;
00209 using SHOTEstimation<PointInT, PointNT, pcl::SHOT, PointRFT>::descLength_;
00210 using SHOTEstimation<PointInT, PointNT, pcl::SHOT, PointRFT>::nr_grid_sector_;
00211 using SHOTEstimation<PointInT, PointNT, pcl::SHOT, PointRFT>::nr_shape_bins_;
00212 using SHOTEstimation<PointInT, PointNT, pcl::SHOT, PointRFT>::sqradius_;
00213 using SHOTEstimation<PointInT, PointNT, pcl::SHOT, PointRFT>::radius3_4_;
00214 using SHOTEstimation<PointInT, PointNT, pcl::SHOT, PointRFT>::radius1_4_;
00215 using SHOTEstimation<PointInT, PointNT, pcl::SHOT, PointRFT>::radius1_2_;
00216
00217 typedef typename Feature<PointInT, pcl::SHOT>::PointCloudOut PointCloudOut;
00218 typedef typename Feature<PointInT, pcl::SHOT>::PointCloudIn PointCloudIn;
00219
00221 SHOTEstimationOMP (unsigned int nr_threads = - 1, int nr_shape_bins = 10)
00222 : SHOTEstimation<PointInT, PointNT, pcl::SHOT, PointRFT> (nr_shape_bins), threads_ ()
00223 {
00224 setNumberOfThreads (nr_threads);
00225 }
00226
00230 inline void
00231 setNumberOfThreads (unsigned int nr_threads)
00232 {
00233 if (nr_threads == 0)
00234 nr_threads = 1;
00235 threads_ = nr_threads;
00236 }
00237
00238 protected:
00239
00245 void
00246 computeFeature (PointCloudOut &output);
00247
00249 bool
00250 initCompute ();
00251
00253 int threads_;
00254 };
00255
00256 template <typename PointNT, typename PointRFT>
00257 class PCL_DEPRECATED_CLASS (SHOTEstimationOMP, "SHOTEstimationOMP<pcl::PointXYZRGBA,...,pcl::SHOT,...> IS DEPRECATED, USE SHOTEstimationOMP<pcl::PointXYZRGBA,...,pcl::SHOT352,...> FOR SHAPE AND SHOTColorEstimationOMP<pcl::PointXYZRGBA,...,pcl::SHOT1344,...> FOR SHAPE+COLOR INSTEAD")
00258 <pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>
00259 : public SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>
00260 {
00261 public:
00262 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::feature_name_;
00263 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::getClassName;
00264 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::input_;
00265 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::indices_;
00266 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::k_;
00267 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::search_parameter_;
00268 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::search_radius_;
00269 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::surface_;
00270 using FeatureFromNormals<pcl::PointXYZRGBA, PointNT, pcl::SHOT>::normals_;
00271 using FeatureWithLocalReferenceFrames<pcl::PointXYZRGBA, PointRFT>::frames_;
00272 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::descLength_;
00273 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::nr_grid_sector_;
00274 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::nr_shape_bins_;
00275 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::sqradius_;
00276 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::radius3_4_;
00277 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::radius1_4_;
00278 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::radius1_2_;
00279 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::b_describe_shape_;
00280 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::b_describe_color_;
00281 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::nr_color_bins_;
00282
00283 typedef typename Feature<pcl::PointXYZRGBA, pcl::SHOT>::PointCloudOut PointCloudOut;
00284 typedef typename Feature<pcl::PointXYZRGBA, pcl::SHOT>::PointCloudIn PointCloudIn;
00285
00287 SHOTEstimationOMP (bool describeShape = true,
00288 bool describeColor = false,
00289 unsigned int nr_threads = - 1,
00290 const int nr_shape_bins = 10,
00291 const int nr_color_bins = 30)
00292 : SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT> (describeShape, describeColor, nr_shape_bins, nr_color_bins),
00293 threads_ ()
00294 {
00295 setNumberOfThreads (nr_threads);
00296 }
00297
00301 inline void
00302 setNumberOfThreads (unsigned int nr_threads)
00303 {
00304 if (nr_threads == 0)
00305 nr_threads = 1;
00306 threads_ = nr_threads;
00307 }
00308
00309 private:
00310
00316 void
00317 computeFeature (PointCloudOut &output);
00318
00320 int threads_;
00321 };
00322 }
00323
00324 #endif //#ifndef PCL_SHOT_OMP_H_
00325
00326