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_FEATURE_H_
00041 #define PCL_FEATURE_H_
00042
00043 #include <boost/function.hpp>
00044 #include <boost/bind.hpp>
00045 #include <boost/mpl/size.hpp>
00046
00047
00048 #include <pcl/pcl_base.h>
00049 #include <pcl/common/eigen.h>
00050 #include <pcl/common/centroid.h>
00051 #include <pcl/search/search.h>
00052
00053 namespace pcl
00054 {
00066 inline void
00067 solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix,
00068 const Eigen::Vector4f &point,
00069 Eigen::Vector4f &plane_parameters, float &curvature);
00070
00083 inline void
00084 solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix,
00085 float &nx, float &ny, float &nz, float &curvature);
00086
00090
00103 template <typename PointInT, typename PointOutT>
00104 class Feature : public PCLBase<PointInT>
00105 {
00106 public:
00107 using PCLBase<PointInT>::indices_;
00108 using PCLBase<PointInT>::input_;
00109
00110 typedef PCLBase<PointInT> BaseClass;
00111
00112 typedef boost::shared_ptr< Feature<PointInT, PointOutT> > Ptr;
00113 typedef boost::shared_ptr< const Feature<PointInT, PointOutT> > ConstPtr;
00114
00115 typedef typename pcl::search::Search<PointInT> KdTree;
00116 typedef typename pcl::search::Search<PointInT>::Ptr KdTreePtr;
00117
00118 typedef pcl::PointCloud<PointInT> PointCloudIn;
00119 typedef typename PointCloudIn::Ptr PointCloudInPtr;
00120 typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00121
00122 typedef pcl::PointCloud<PointOutT> PointCloudOut;
00123
00124 typedef boost::function<int (size_t, double, std::vector<int> &, std::vector<float> &)> SearchMethod;
00125 typedef boost::function<int (const PointCloudIn &cloud, size_t index, double, std::vector<int> &, std::vector<float> &)> SearchMethodSurface;
00126
00127 public:
00129 Feature () :
00130 feature_name_ (), search_method_surface_ (),
00131 surface_(), tree_(),
00132 search_parameter_(0), search_radius_(0), k_(0),
00133 fake_surface_(false)
00134 {}
00135
00143 inline void
00144 setSearchSurface (const PointCloudInConstPtr &cloud)
00145 {
00146 surface_ = cloud;
00147 fake_surface_ = false;
00148
00149 }
00150
00152 inline PointCloudInConstPtr
00153 getSearchSurface () const
00154 {
00155 return (surface_);
00156 }
00157
00161 inline void
00162 setSearchMethod (const KdTreePtr &tree) { tree_ = tree; }
00163
00165 inline KdTreePtr
00166 getSearchMethod () const
00167 {
00168 return (tree_);
00169 }
00170
00172 inline double
00173 getSearchParameter () const
00174 {
00175 return (search_parameter_);
00176 }
00177
00181 inline void
00182 setKSearch (int k) { k_ = k; }
00183
00185 inline int
00186 getKSearch () const
00187 {
00188 return (k_);
00189 }
00190
00195 inline void
00196 setRadiusSearch (double radius)
00197 {
00198 search_radius_ = radius;
00199 }
00200
00202 inline double
00203 getRadiusSearch () const
00204 {
00205 return (search_radius_);
00206 }
00207
00213 void
00214 compute (PointCloudOut &output);
00215
00221 void
00222 computeEigen (pcl::PointCloud<Eigen::MatrixXf> &output);
00223
00224 protected:
00226 std::string feature_name_;
00227
00229 SearchMethodSurface search_method_surface_;
00230
00234 PointCloudInConstPtr surface_;
00235
00237 KdTreePtr tree_;
00238
00240 double search_parameter_;
00241
00243 double search_radius_;
00244
00246 int k_;
00247
00249 inline const std::string&
00250 getClassName () const { return (feature_name_); }
00251
00253 virtual bool
00254 initCompute ();
00255
00257 virtual bool
00258 deinitCompute ();
00259
00261 bool fake_surface_;
00262
00273 inline int
00274 searchForNeighbors (size_t index, double parameter,
00275 std::vector<int> &indices, std::vector<float> &distances) const
00276 {
00277 return (search_method_surface_ (*input_, index, parameter, indices, distances));
00278 }
00279
00291 inline int
00292 searchForNeighbors (const PointCloudIn &cloud, size_t index, double parameter,
00293 std::vector<int> &indices, std::vector<float> &distances) const
00294 {
00295 return (search_method_surface_ (cloud, index, parameter, indices, distances));
00296 }
00297
00298 private:
00302 virtual void
00303 computeFeature (PointCloudOut &output) = 0;
00304
00308 virtual void
00309 computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output) = 0;
00310
00311 public:
00312 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00313 };
00314
00315
00319 template <typename PointInT, typename PointNT, typename PointOutT>
00320 class FeatureFromNormals : public Feature<PointInT, PointOutT>
00321 {
00322 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00323 typedef typename PointCloudIn::Ptr PointCloudInPtr;
00324 typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00325 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00326
00327 public:
00328 typedef typename pcl::PointCloud<PointNT> PointCloudN;
00329 typedef typename PointCloudN::Ptr PointCloudNPtr;
00330 typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;
00331
00332 typedef boost::shared_ptr< FeatureFromNormals<PointInT, PointNT, PointOutT> > Ptr;
00333 typedef boost::shared_ptr< const FeatureFromNormals<PointInT, PointNT, PointOutT> > ConstPtr;
00334
00335
00336 using Feature<PointInT, PointOutT>::input_;
00337 using Feature<PointInT, PointOutT>::surface_;
00338 using Feature<PointInT, PointOutT>::getClassName;
00339
00341 FeatureFromNormals () : normals_ () {}
00342
00350 inline void
00351 setInputNormals (const PointCloudNConstPtr &normals) { normals_ = normals; }
00352
00354 inline PointCloudNConstPtr
00355 getInputNormals () const { return (normals_); }
00356
00357 protected:
00361 PointCloudNConstPtr normals_;
00362
00364 virtual bool
00365 initCompute ();
00366
00367 public:
00368 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00369 };
00370
00374 template <typename PointInT, typename PointLT, typename PointOutT>
00375 class FeatureFromLabels : public Feature<PointInT, PointOutT>
00376 {
00377 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00378 typedef typename PointCloudIn::Ptr PointCloudInPtr;
00379 typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00380
00381 typedef typename pcl::PointCloud<PointLT> PointCloudL;
00382 typedef typename PointCloudL::Ptr PointCloudNPtr;
00383 typedef typename PointCloudL::ConstPtr PointCloudLConstPtr;
00384
00385 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00386
00387 public:
00388 typedef boost::shared_ptr< FeatureFromLabels<PointInT, PointLT, PointOutT> > Ptr;
00389 typedef boost::shared_ptr< const FeatureFromLabels<PointInT, PointLT, PointOutT> > ConstPtr;
00390
00391
00392 using Feature<PointInT, PointOutT>::input_;
00393 using Feature<PointInT, PointOutT>::surface_;
00394 using Feature<PointInT, PointOutT>::getClassName;
00395 using Feature<PointInT, PointOutT>::k_;
00396
00398 FeatureFromLabels () : labels_ ()
00399 {
00400 k_ = 1;
00401 }
00402
00409 inline void
00410 setInputLabels (const PointCloudLConstPtr &labels)
00411 {
00412 labels_ = labels;
00413 }
00414
00416 inline PointCloudLConstPtr
00417 getInputLabels () const
00418 {
00419 return (labels_);
00420 }
00421
00422 protected:
00426 PointCloudLConstPtr labels_;
00427
00429 virtual bool
00430 initCompute ();
00431
00432 public:
00433 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00434 };
00435
00439
00450 template <typename PointInT, typename PointRFT>
00451 class FeatureWithLocalReferenceFrames
00452 {
00453 public:
00454 typedef pcl::PointCloud<PointRFT> PointCloudLRF;
00455 typedef typename PointCloudLRF::Ptr PointCloudLRFPtr;
00456 typedef typename PointCloudLRF::ConstPtr PointCloudLRFConstPtr;
00457
00459 FeatureWithLocalReferenceFrames () : frames_ (), frames_never_defined_ (true) {}
00460
00462 virtual ~FeatureWithLocalReferenceFrames () {}
00463
00470 inline void
00471 setInputReferenceFrames (const PointCloudLRFConstPtr &frames)
00472 {
00473 frames_ = frames;
00474 frames_never_defined_ = false;
00475 }
00476
00478 inline PointCloudLRFConstPtr
00479 getInputReferenceFrames () const
00480 {
00481 return (frames_);
00482 }
00483
00484 protected:
00486 PointCloudLRFConstPtr frames_;
00488 bool frames_never_defined_;
00489
00495 typedef typename Feature<PointInT, PointRFT>::Ptr LRFEstimationPtr;
00496 virtual bool
00497 initLocalReferenceFrames (const size_t& indices_size,
00498 const LRFEstimationPtr& lrf_estimation = LRFEstimationPtr());
00499 };
00500 }
00501
00502 #include <pcl/features/impl/feature.hpp>
00503
00504 #endif //#ifndef PCL_FEATURE_H_