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_SHOT_H_
00040 #define PCL_SHOT_H_
00041
00042 #include <pcl/point_types.h>
00043 #include <pcl/features/feature.h>
00044
00045 namespace pcl
00046 {
00066 template <typename PointInT, typename PointNT, typename PointOutT, typename PointRFT = pcl::ReferenceFrame>
00067 class SHOTEstimationBase : public FeatureFromNormals<PointInT, PointNT, PointOutT>,
00068 public FeatureWithLocalReferenceFrames<PointInT, PointRFT>
00069 {
00070 public:
00071 using Feature<PointInT, PointOutT>::feature_name_;
00072 using Feature<PointInT, PointOutT>::getClassName;
00073 using Feature<PointInT, PointOutT>::input_;
00074 using Feature<PointInT, PointOutT>::indices_;
00075 using Feature<PointInT, PointOutT>::k_;
00076 using Feature<PointInT, PointOutT>::search_parameter_;
00077 using Feature<PointInT, PointOutT>::search_radius_;
00078 using Feature<PointInT, PointOutT>::surface_;
00079 using Feature<PointInT, PointOutT>::fake_surface_;
00080 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00081 using FeatureWithLocalReferenceFrames<PointInT, PointRFT>::frames_;
00082
00083 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00084
00085 protected:
00089 SHOTEstimationBase (int nr_shape_bins = 10) :
00090 nr_shape_bins_ (nr_shape_bins),
00091 shot_ (),
00092 sqradius_ (0), radius3_4_ (0), radius1_4_ (0), radius1_2_ (0),
00093 nr_grid_sector_ (32),
00094 maxAngularSectors_ (28),
00095 descLength_ (0)
00096 {
00097 feature_name_ = "SHOTEstimation";
00098 };
00099
00100 public:
00107 virtual void
00108 computePointSHOT (const int index,
00109 const std::vector<int> &indices,
00110 const std::vector<float> &sqr_dists,
00111 Eigen::VectorXf &shot) = 0;
00112
00113 protected:
00114
00116 virtual bool
00117 initCompute ();
00118
00128 void
00129 interpolateSingleChannel (const std::vector<int> &indices,
00130 const std::vector<float> &sqr_dists,
00131 const int index,
00132 std::vector<double> &binDistance,
00133 const int nr_bins,
00134 Eigen::VectorXf &shot);
00135
00140 void
00141 normalizeHistogram (Eigen::VectorXf &shot, int desc_length);
00142
00143
00150 void
00151 createBinDistanceShape (int index, const std::vector<int> &indices,
00152 std::vector<double> &bin_distance_shape);
00153
00155 int nr_shape_bins_;
00156
00158 Eigen::VectorXf shot_;
00159
00161 double sqradius_;
00162
00164 double radius3_4_;
00165
00167 double radius1_4_;
00168
00170 double radius1_2_;
00171
00173 const int nr_grid_sector_;
00174
00176 const int maxAngularSectors_;
00177
00179 int descLength_;
00180
00184 void
00185 computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &) {}
00186 };
00187
00205
00206
00207
00208
00209
00210
00211
00212
00213
00214
00215
00216
00217
00218
00219
00220
00221
00222
00223
00224
00225
00226
00228
00229
00230
00231
00233
00234
00235
00236
00237
00238
00239
00241
00242
00243
00244
00245
00246
00247
00248
00249
00250
00252
00253
00254
00255
00256
00257
00275 template <typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT352, typename PointRFT = pcl::ReferenceFrame>
00276 class SHOTEstimation : public SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>
00277 {
00278 public:
00279 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::feature_name_;
00280 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::getClassName;
00281 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::indices_;
00282 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::k_;
00283 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::search_parameter_;
00284 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::search_radius_;
00285 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::surface_;
00286 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::input_;
00287 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::normals_;
00288 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::descLength_;
00289 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::nr_grid_sector_;
00290 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::nr_shape_bins_;
00291 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::sqradius_;
00292 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::radius3_4_;
00293 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::radius1_4_;
00294 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::radius1_2_;
00295 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::maxAngularSectors_;
00296 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::interpolateSingleChannel;
00297 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::shot_;
00298 using FeatureWithLocalReferenceFrames<PointInT, PointRFT>::frames_;
00299
00300 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00301
00303 SHOTEstimation () : SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT> (10)
00304 {
00305 feature_name_ = "SHOTEstimation";
00306 };
00307
00314 virtual void
00315 computePointSHOT (const int index,
00316 const std::vector<int> &indices,
00317 const std::vector<float> &sqr_dists,
00318 Eigen::VectorXf &shot);
00319 protected:
00325 void
00326 computeFeature (pcl::PointCloud<PointOutT> &output);
00327 };
00328
00346 template <typename PointInT, typename PointNT, typename PointRFT>
00347 class PCL_DEPRECATED_CLASS (SHOTEstimation, "SHOTEstimation<..., pcl::SHOT, ...> IS DEPRECATED, USE SHOTEstimation<..., pcl::SHOT352, ...> INSTEAD")
00348 <PointInT, PointNT, pcl::SHOT, PointRFT>
00349 : public SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT>
00350 {
00351 public:
00352 using SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT>::feature_name_;
00353 using SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT>::getClassName;
00354 using SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT>::indices_;
00355 using SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT>::k_;
00356 using SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT>::search_parameter_;
00357 using SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT>::search_radius_;
00358 using SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT>::surface_;
00359 using SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT>::input_;
00360 using SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT>::normals_;
00361 using SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT>::descLength_;
00362 using SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT>::nr_grid_sector_;
00363 using SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT>::nr_shape_bins_;
00364 using SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT>::sqradius_;
00365 using SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT>::radius3_4_;
00366 using SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT>::radius1_4_;
00367 using SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT>::radius1_2_;
00368 using SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT>::maxAngularSectors_;
00369 using SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT>::interpolateSingleChannel;
00370 using SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT>::shot_;
00371 using FeatureWithLocalReferenceFrames<PointInT, PointRFT>::frames_;
00372
00373 typedef typename Feature<PointInT, pcl::SHOT>::PointCloudIn PointCloudIn;
00374
00378 SHOTEstimation (int nr_shape_bins = 10) : SHOTEstimationBase<PointInT, PointNT, pcl::SHOT, PointRFT> (nr_shape_bins)
00379 {
00380 feature_name_ = "SHOTEstimation";
00381 };
00382
00389 virtual void
00390 computePointSHOT (const int index,
00391 const std::vector<int> &indices,
00392 const std::vector<float> &sqr_dists,
00393 Eigen::VectorXf &shot);
00394
00395 protected:
00401 void
00402 computeFeature (pcl::PointCloud<pcl::SHOT> &output);
00403 };
00404
00422 template <typename PointInT, typename PointNT, typename PointRFT>
00423 class SHOTEstimation<PointInT, PointNT, Eigen::MatrixXf, PointRFT> : public SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>
00424 {
00425 public:
00426 using SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>::feature_name_;
00427 using SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>::getClassName;
00428 using SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>::indices_;
00429 using SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>::k_;
00430 using SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>::search_parameter_;
00431 using SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>::search_radius_;
00432 using SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>::surface_;
00433 using SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>::input_;
00434 using SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>::normals_;
00435 using SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>::descLength_;
00436 using SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>::nr_grid_sector_;
00437 using SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>::nr_shape_bins_;
00438 using SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>::sqradius_;
00439 using SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>::radius3_4_;
00440 using SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>::radius1_4_;
00441 using SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>::radius1_2_;
00442 using SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>::maxAngularSectors_;
00443 using SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>::interpolateSingleChannel;
00444 using SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>::shot_;
00445 using FeatureWithLocalReferenceFrames<PointInT, PointRFT>::frames_;
00446
00448 SHOTEstimation (int nr_shape_bins = 10) : SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT> ()
00449 {
00450 feature_name_ = "SHOTEstimation";
00451 nr_shape_bins_ = nr_shape_bins;
00452 };
00453
00459 void
00460 computeEigen (pcl::PointCloud<Eigen::MatrixXf> &output)
00461 {
00462 pcl::SHOTEstimation<PointInT, PointNT, pcl::SHOT352, PointRFT>::computeEigen (output);
00463 }
00464
00471
00472
00473
00474
00475
00476
00477 protected:
00483 void
00484 computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output);
00485
00486
00490 void
00491 compute (pcl::PointCloud<pcl::SHOT352> &) { assert(0); }
00492 };
00493
00511 template <typename PointInT, typename PointNT, typename PointOutT = pcl::SHOT1344, typename PointRFT = pcl::ReferenceFrame>
00512 class SHOTColorEstimation : public SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>
00513 {
00514 public:
00515 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::feature_name_;
00516 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::getClassName;
00517 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::indices_;
00518 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::k_;
00519 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::search_parameter_;
00520 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::search_radius_;
00521 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::surface_;
00522 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::input_;
00523 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::normals_;
00524 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::descLength_;
00525 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::nr_grid_sector_;
00526 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::nr_shape_bins_;
00527 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::sqradius_;
00528 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::radius3_4_;
00529 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::radius1_4_;
00530 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::radius1_2_;
00531 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::maxAngularSectors_;
00532 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::interpolateSingleChannel;
00533 using SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT>::shot_;
00534 using FeatureWithLocalReferenceFrames<PointInT, PointRFT>::frames_;
00535
00536 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00537
00542 SHOTColorEstimation (bool describe_shape = true,
00543 bool describe_color = true)
00544 : SHOTEstimationBase<PointInT, PointNT, PointOutT, PointRFT> (10),
00545 b_describe_shape_ (describe_shape),
00546 b_describe_color_ (describe_color),
00547 nr_color_bins_ (30)
00548 {
00549 feature_name_ = "SHOTColorEstimation";
00550 };
00551
00558 virtual void
00559 computePointSHOT (const int index,
00560 const std::vector<int> &indices,
00561 const std::vector<float> &sqr_dists,
00562 Eigen::VectorXf &shot);
00563 protected:
00569 void
00570 computeFeature (pcl::PointCloud<PointOutT> &output);
00571
00582 void
00583 interpolateDoubleChannel (const std::vector<int> &indices,
00584 const std::vector<float> &sqr_dists,
00585 const int index,
00586 std::vector<double> &binDistanceShape,
00587 std::vector<double> &binDistanceColor,
00588 const int nr_bins_shape,
00589 const int nr_bins_color,
00590 Eigen::VectorXf &shot);
00591
00593 bool b_describe_shape_;
00594
00596 bool b_describe_color_;
00597
00599 int nr_color_bins_;
00600
00601 public:
00610 static void
00611 RGB2CIELAB (unsigned char R, unsigned char G, unsigned char B, float &L, float &A, float &B2);
00612
00613 static float sRGB_LUT[256];
00614 static float sXYZ_LUT[4000];
00615 };
00616
00617 template <typename PointInT, typename PointNT, typename PointRFT>
00618 class SHOTColorEstimation<PointInT, PointNT, Eigen::MatrixXf, PointRFT> : public SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>
00619 {
00620 public:
00621 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::feature_name_;
00622 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::getClassName;
00623 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::indices_;
00624 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::k_;
00625 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::search_parameter_;
00626 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::search_radius_;
00627 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::surface_;
00628 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::input_;
00629 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::normals_;
00630 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::descLength_;
00631 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::nr_grid_sector_;
00632 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::nr_shape_bins_;
00633 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::sqradius_;
00634 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::radius3_4_;
00635 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::radius1_4_;
00636 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::radius1_2_;
00637 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::maxAngularSectors_;
00638 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::interpolateSingleChannel;
00639 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::shot_;
00640 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::b_describe_shape_;
00641 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::b_describe_color_;
00642 using SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::nr_color_bins_;
00643 using FeatureWithLocalReferenceFrames<PointInT, PointRFT>::frames_;
00644
00649 SHOTColorEstimation (bool describe_shape = true,
00650 bool describe_color = true,
00651 int nr_shape_bins = 10,
00652 int nr_color_bins = 30)
00653 : SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT> (describe_shape, describe_color)
00654 {
00655 feature_name_ = "SHOTColorEstimation";
00656 nr_shape_bins_ = nr_shape_bins;
00657 nr_color_bins_ = nr_color_bins;
00658 };
00659
00665 void
00666 computeEigen (pcl::PointCloud<Eigen::MatrixXf> &output)
00667 {
00668 pcl::SHOTColorEstimation<PointInT, PointNT, pcl::SHOT1344, PointRFT>::computeEigen (output);
00669 }
00670
00671 protected:
00677 void
00678 computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output);
00679
00680
00684 void
00685 compute (pcl::PointCloud<pcl::SHOT1344> &) { assert(0); }
00686 };
00687
00705 template <typename PointNT, typename PointRFT>
00706 class PCL_DEPRECATED_CLASS (SHOTEstimation, "SHOTEstimation<pcl::PointXYZRGBA,...,pcl::SHOT,...> IS DEPRECATED, USE SHOTEstimation<pcl::PointXYZRGBA,...,pcl::SHOT352,...> FOR SHAPE AND SHOTColorEstimation<pcl::PointXYZRGBA,...,pcl::SHOT1344,...> FOR SHAPE+COLOR INSTEAD")
00707 <pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>
00708 : public SHOTEstimationBase<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>
00709 {
00710 public:
00711 using SHOTEstimationBase<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::feature_name_;
00712 using SHOTEstimationBase<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::indices_;
00713 using SHOTEstimationBase<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::k_;
00714 using SHOTEstimationBase<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::search_parameter_;
00715 using SHOTEstimationBase<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::search_radius_;
00716 using SHOTEstimationBase<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::surface_;
00717 using SHOTEstimationBase<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::input_;
00718 using FeatureFromNormals<pcl::PointXYZRGBA, PointNT, pcl::SHOT>::normals_;
00719 using FeatureWithLocalReferenceFrames<pcl::PointXYZRGBA, PointRFT>::frames_;
00720 using SHOTEstimationBase<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::getClassName;
00721 using SHOTEstimationBase<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::descLength_;
00722 using SHOTEstimationBase<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::nr_grid_sector_;
00723 using SHOTEstimationBase<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::nr_shape_bins_;
00724 using SHOTEstimationBase<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::sqradius_;
00725 using SHOTEstimationBase<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::radius3_4_;
00726 using SHOTEstimationBase<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::radius1_4_;
00727 using SHOTEstimationBase<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::radius1_2_;
00728 using SHOTEstimationBase<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::maxAngularSectors_;
00729 using SHOTEstimationBase<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::interpolateSingleChannel;
00730 using SHOTEstimationBase<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::shot_;
00731
00732 typedef typename Feature<pcl::PointXYZRGBA, pcl::SHOT>::PointCloudOut PointCloudOut;
00733 typedef typename Feature<pcl::PointXYZRGBA, pcl::SHOT>::PointCloudIn PointCloudIn;
00734
00741 SHOTEstimation (bool describe_shape = true,
00742 bool describe_color = false,
00743 const int nr_shape_bins = 10,
00744 const int nr_color_bins = 30)
00745 : SHOTEstimationBase<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT> (nr_shape_bins),
00746 b_describe_shape_ (describe_shape),
00747 b_describe_color_ (describe_color),
00748 nr_color_bins_ (nr_color_bins)
00749 {
00750 feature_name_ = "SHOTEstimation";
00751 };
00752
00759 virtual void
00760 computePointSHOT (const int index,
00761 const std::vector<int> &indices,
00762 const std::vector<float> &sqr_dists,
00763 Eigen::VectorXf &shot);
00764
00765 protected:
00766
00772 void
00773 computeFeature (PointCloudOut &output);
00774
00785 void
00786 interpolateDoubleChannel (const std::vector<int> &indices,
00787 const std::vector<float> &sqr_dists,
00788 const int index,
00789 std::vector<double> &binDistanceShape,
00790 std::vector<double> &binDistanceColor,
00791 const int nr_bins_shape,
00792 const int nr_bins_color,
00793 Eigen::VectorXf &shot);
00794
00803 static void
00804 RGB2CIELAB (unsigned char R, unsigned char G, unsigned char B, float &L, float &A, float &B2);
00805
00807 bool b_describe_shape_;
00808
00810 bool b_describe_color_;
00811
00813 int nr_color_bins_;
00814
00815 public:
00816 static float sRGB_LUT[256];
00817 static float sXYZ_LUT[4000];
00818 };
00819
00837 template <typename PointNT, typename PointRFT>
00838 class PCL_DEPRECATED_CLASS (SHOTEstimation, "SHOTEstimation<pcl::PointXYZRGBA,...,Eigen::MatrixXf,...> IS DEPRECATED, USE SHOTColorEstimation<pcl::PointXYZRGBA,...,Eigen::MatrixXf,...> FOR SHAPE AND SHAPE+COLOR INSTEAD")
00839 <pcl::PointXYZRGBA, PointNT, Eigen::MatrixXf, PointRFT>
00840 : public SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>
00841 {
00842 public:
00843 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::feature_name_;
00844 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::getClassName;
00845 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::indices_;
00846 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::k_;
00847 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::search_parameter_;
00848 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::search_radius_;
00849 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::surface_;
00850 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::input_;
00851 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::descLength_;
00852 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::nr_grid_sector_;
00853 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::nr_shape_bins_;
00854 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::sqradius_;
00855 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::radius3_4_;
00856 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::radius1_4_;
00857 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::radius1_2_;
00858 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::maxAngularSectors_;
00859 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::interpolateSingleChannel;
00860 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::shot_;
00861 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::b_describe_shape_;
00862 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::b_describe_color_;
00863 using SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT>::nr_color_bins_;
00864 using FeatureWithLocalReferenceFrames<pcl::PointXYZRGBA, PointRFT>::frames_;
00865
00872 SHOTEstimation (bool describe_shape = true,
00873 bool describe_color = false,
00874 const int nr_shape_bins = 10,
00875 const int nr_color_bins = 30)
00876 : SHOTEstimation<pcl::PointXYZRGBA, PointNT, pcl::SHOT, PointRFT> (describe_shape, describe_color, nr_shape_bins, nr_color_bins) {};
00877
00878 protected:
00884 void
00885 computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output);
00886
00887
00891 void
00892 compute (pcl::PointCloud<pcl::SHOT> &) { assert(0); }
00893 };
00894 }
00895
00896 #endif //#ifndef PCL_SHOT_H_
00897
00898