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
00040
00041 #ifndef PCL_FEATURES_3DSC_H_
00042 #define PCL_FEATURES_3DSC_H_
00043
00044 #include <pcl/point_types.h>
00045 #include <pcl/features/boost.h>
00046 #include <pcl/features/feature.h>
00047
00048 namespace pcl
00049 {
00071 template <typename PointInT, typename PointNT, typename PointOutT = pcl::ShapeContext1980>
00072 class ShapeContext3DEstimation : public FeatureFromNormals<PointInT, PointNT, PointOutT>
00073 {
00074 public:
00075 typedef boost::shared_ptr<ShapeContext3DEstimation<PointInT, PointNT, PointOutT> > Ptr;
00076 typedef boost::shared_ptr<const ShapeContext3DEstimation<PointInT, PointNT, PointOutT> > ConstPtr;
00077
00078 using Feature<PointInT, PointOutT>::feature_name_;
00079 using Feature<PointInT, PointOutT>::getClassName;
00080 using Feature<PointInT, PointOutT>::indices_;
00081 using Feature<PointInT, PointOutT>::search_parameter_;
00082 using Feature<PointInT, PointOutT>::search_radius_;
00083 using Feature<PointInT, PointOutT>::surface_;
00084 using Feature<PointInT, PointOutT>::input_;
00085 using Feature<PointInT, PointOutT>::searchForNeighbors;
00086 using FeatureFromNormals<PointInT, PointNT, PointOutT>::normals_;
00087
00088 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00089 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00090
00095 ShapeContext3DEstimation (bool random = false) :
00096 radii_interval_(0),
00097 theta_divisions_(0),
00098 phi_divisions_(0),
00099 volume_lut_(0),
00100 azimuth_bins_(12),
00101 elevation_bins_(11),
00102 radius_bins_(15),
00103 min_radius_(0.1),
00104 point_density_radius_(0.2),
00105 descriptor_length_ (),
00106 rng_alg_ (),
00107 rng_ (new boost::uniform_01<boost::mt19937> (rng_alg_))
00108 {
00109 feature_name_ = "ShapeContext3DEstimation";
00110 search_radius_ = 2.5;
00111
00112
00113 if (random)
00114 rng_->base ().seed (static_cast<unsigned> (std::time(0)));
00115 else
00116 rng_->base ().seed (12345u);
00117 }
00118
00119 virtual ~ShapeContext3DEstimation() {}
00120
00121
00122
00123
00125 inline size_t
00126 getAzimuthBins () { return (azimuth_bins_); }
00127
00128
00129
00130
00132 inline size_t
00133 getElevationBins () { return (elevation_bins_); }
00134
00135
00136
00137
00139 inline size_t
00140 getRadiusBins () { return (radius_bins_); }
00141
00145 inline void
00146 setMinimalRadius (double radius) { min_radius_ = radius; }
00147
00149 inline double
00150 getMinimalRadius () { return (min_radius_); }
00151
00156 inline void
00157 setPointDensityRadius (double radius) { point_density_radius_ = radius; }
00158
00160 inline double
00161 getPointDensityRadius () { return (point_density_radius_); }
00162
00163 protected:
00165 bool
00166 initCompute ();
00167
00176 bool
00177 computePoint (size_t index, const pcl::PointCloud<PointNT> &normals, float rf[9], std::vector<float> &desc);
00178
00182 void
00183 computeFeature (PointCloudOut &output);
00184
00186 std::vector<float> radii_interval_;
00187
00189 std::vector<float> theta_divisions_;
00190
00192 std::vector<float> phi_divisions_;
00193
00195 std::vector<float> volume_lut_;
00196
00198 size_t azimuth_bins_;
00199
00201 size_t elevation_bins_;
00202
00204 size_t radius_bins_;
00205
00207 double min_radius_;
00208
00210 double point_density_radius_;
00211
00213 size_t descriptor_length_;
00214
00216 boost::mt19937 rng_alg_;
00217
00219 boost::shared_ptr<boost::uniform_01<boost::mt19937> > rng_;
00220
00226
00227
00228
00230 inline double
00231 rnd ()
00232 {
00233 return ((*rng_) ());
00234 }
00235 };
00236 }
00237
00238 #ifdef PCL_NO_PRECOMPILE
00239 #include <pcl/features/impl/3dsc.hpp>
00240 #endif
00241
00242 #endif //#ifndef PCL_3DSC_H_