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_H_
00041 #define PCL_SHOT_H_
00042
00043 #include <pcl/point_types.h>
00044 #include <pcl/features/feature.h>
00045
00046 namespace pcl
00047 {
00067 template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
00068 class SHOTEstimationBase : public FeatureFromNormals<PointInT, PointNT, PointOutT>,
00069 public FeatureWithLocalReferenceFrames<PointInT, PointRFT>
00070 {
00071 public:
00072 typedef boost::shared_ptr<SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT> > Ptr;
00073 typedef boost::shared_ptr<const SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT> > ConstPtr;
00074 using Feature<PointInT, PointOutT>::feature_name_;
00075 using Feature<PointInT, PointOutT>::getClassName;
00076 using Feature<PointInT, PointOutT>::input_;
00077 using Feature<PointInT, PointOutT>::indices_;
00078 using Feature<PointInT, PointOutT>::k_;
00079 using Feature<PointInT, PointOutT>::search_parameter_;
00080 using Feature<PointInT, PointOutT>::search_radius_;
00081 using Feature<PointInT, PointOutT>::surface_;
00082 using Feature<PointInT, PointOutT>::fake_surface_;
00083 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00084 using FeatureWithLocalReferenceFrames<PointInT, PointRFT>::frames_;
00085
00086 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00087
00088 protected:
00092 SHOTEstimationBase (int nr_shape_bins = 10) :
00093 nr_shape_bins_ (nr_shape_bins),
00094 shot_ (), lrf_radius_ (0),
00095 sqradius_ (0), radius3_4_ (0), radius1_4_ (0), radius1_2_ (0),
00096 nr_grid_sector_ (32),
00097 maxAngularSectors_ (28),
00098 descLength_ (0)
00099 {
00100 feature_name_ = "SHOTEstimation";
00101 };
00102
00103
00104 public:
00105
00107 virtual ~SHOTEstimationBase () {}
00108
00115 virtual void
00116 computePointSHOT (const int index,
00117 const std::vector<int> &indices,
00118 const std::vector<float> &sqr_dists,
00119 Eigen::VectorXf &shot) = 0;
00120
00122 virtual void
00123 setLRFRadius (float radius) { lrf_radius_ = radius; }
00124
00126 virtual float
00127 getLRFRadius () const { return lrf_radius_; }
00128
00129 protected:
00130
00132 virtual bool
00133 initCompute ();
00134
00144 void
00145 interpolateSingleChannel (const std::vector<int> &indices,
00146 const std::vector<float> &sqr_dists,
00147 const int index,
00148 std::vector<double> &binDistance,
00149 const int nr_bins,
00150 Eigen::VectorXf &shot);
00151
00156 void
00157 normalizeHistogram (Eigen::VectorXf &shot, int desc_length);
00158
00159
00166 void
00167 createBinDistanceShape (int index, const std::vector<int> &indices,
00168 std::vector<double> &bin_distance_shape);
00169
00171 int nr_shape_bins_;
00172
00174 Eigen::VectorXf shot_;
00175
00177 float lrf_radius_;
00178
00180 double sqradius_;
00181
00183 double radius3_4_;
00184
00186 double radius1_4_;
00187
00189 double radius1_2_;
00190
00192 const int nr_grid_sector_;
00193
00195 const int maxAngularSectors_;
00196
00198 int descLength_;
00199 };
00200
00220 template <typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT352, typename PointRFT = pcl::ReferenceFrame>
00221 class SHOTEstimation : public SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>
00222 {
00223 public:
00224 typedef boost::shared_ptr<SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT> > Ptr;
00225 typedef boost::shared_ptr<const SHOTEstimation<PointInT, PointNT, PointOutT, PointRFT> > ConstPtr;
00226 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::feature_name_;
00227 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::getClassName;
00228 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::indices_;
00229 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::k_;
00230 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::search_parameter_;
00231 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::search_radius_;
00232 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::surface_;
00233 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::input_;
00234 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::normals_;
00235 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::descLength_;
00236 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::nr_grid_sector_;
00237 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::nr_shape_bins_;
00238 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::sqradius_;
00239 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::radius3_4_;
00240 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::radius1_4_;
00241 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::radius1_2_;
00242 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::maxAngularSectors_;
00243 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::interpolateSingleChannel;
00244 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::shot_;
00245 using FeatureWithLocalReferenceFrames<PointInT, PointRFT>::frames_;
00246
00247 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00248
00250 SHOTEstimation () : SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT> (10)
00251 {
00252 feature_name_ = "SHOTEstimation";
00253 };
00254
00256 virtual ~SHOTEstimation () {}
00257
00264 virtual void
00265 computePointSHOT (const int index,
00266 const std::vector<int> &indices,
00267 const std::vector<float> &sqr_dists,
00268 Eigen::VectorXf &shot);
00269 protected:
00275 void
00276 computeFeature (pcl::PointCloud<PointOutT> &output);
00277 };
00278
00298 template <typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
00299 class SHOTColorEstimation : public SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>
00300 {
00301 public:
00302 typedef boost::shared_ptr<SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT> > Ptr;
00303 typedef boost::shared_ptr<const SHOTColorEstimation<PointInT, PointNT, PointOutT, PointRFT> > ConstPtr;
00304 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::feature_name_;
00305 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::getClassName;
00306 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::indices_;
00307 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::k_;
00308 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::search_parameter_;
00309 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::search_radius_;
00310 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::surface_;
00311 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::input_;
00312 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::normals_;
00313 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::descLength_;
00314 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::nr_grid_sector_;
00315 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::nr_shape_bins_;
00316 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::sqradius_;
00317 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::radius3_4_;
00318 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::radius1_4_;
00319 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::radius1_2_;
00320 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::maxAngularSectors_;
00321 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::interpolateSingleChannel;
00322 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::shot_;
00323 using FeatureWithLocalReferenceFrames<PointInT, PointRFT>::frames_;
00324
00325 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00326
00331 SHOTColorEstimation (bool describe_shape = true,
00332 bool describe_color = true)
00333 : SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT> (10),
00334 b_describe_shape_ (describe_shape),
00335 b_describe_color_ (describe_color),
00336 nr_color_bins_ (30)
00337 {
00338 feature_name_ = "SHOTColorEstimation";
00339 };
00340
00342 virtual ~SHOTColorEstimation () {}
00343
00350 virtual void
00351 computePointSHOT (const int index,
00352 const std::vector<int> &indices,
00353 const std::vector<float> &sqr_dists,
00354 Eigen::VectorXf &shot);
00355 protected:
00361 void
00362 computeFeature (pcl::PointCloud<PointOutT> &output);
00363
00374 void
00375 interpolateDoubleChannel (const std::vector<int> &indices,
00376 const std::vector<float> &sqr_dists,
00377 const int index,
00378 std::vector<double> &binDistanceShape,
00379 std::vector<double> &binDistanceColor,
00380 const int nr_bins_shape,
00381 const int nr_bins_color,
00382 Eigen::VectorXf &shot);
00383
00385 bool b_describe_shape_;
00386
00388 bool b_describe_color_;
00389
00391 int nr_color_bins_;
00392
00393 public:
00402 static void
00403 RGB2CIELAB (unsigned char R, unsigned char G, unsigned char B, float &L, float &A, float &B2);
00404
00405 static float sRGB_LUT[256];
00406 static float sXYZ_LUT[4000];
00407 };
00408 }
00409
00410 #ifdef PCL_NO_PRECOMPILE
00411 #include <pcl/features/impl/shot.hpp>
00412 #endif
00413
00414 #endif //#ifndef PCL_SHOT_H_