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 #ifndef PCL_FEATURE_H_
00039 #define PCL_FEATURE_H_
00040
00041 #include <boost/function.hpp>
00042 #include <boost/bind.hpp>
00043 #include <boost/mpl/size.hpp>
00044
00045
00046 #include "pcl/pcl_base.h"
00047 #include "pcl/common/eigen.h"
00048
00049 #include "pcl/kdtree/tree_types.h"
00050 #include "pcl/kdtree/kdtree.h"
00051 #include "pcl/kdtree/kdtree_flann.h"
00052 #include "pcl/kdtree/organized_data.h"
00053
00054 #include "pcl/io/io.h"
00055
00056 namespace pcl
00057 {
00062 template <typename PointT> inline void
00063 compute3DCentroid (const pcl::PointCloud<PointT> &cloud, Eigen::Vector4f ¢roid);
00064
00070 template <typename PointT> inline void
00071 compute3DCentroid (const pcl::PointCloud<PointT> &cloud,
00072 const std::vector<int> &indices, Eigen::Vector4f ¢roid);
00073
00079 template <typename PointT> inline void
00080 compute3DCentroid (const pcl::PointCloud<PointT> &cloud,
00081 const pcl::PointIndices &indices, Eigen::Vector4f ¢roid);
00082
00084 template<typename PointT>
00085 struct NdCentroidFunctor
00086 {
00087 typedef typename traits::POD<PointT>::type Pod;
00088
00089 NdCentroidFunctor (const PointT &p, Eigen::VectorXf ¢roid)
00090 : f_idx_ (0),
00091 centroid_ (centroid),
00092 p_ (reinterpret_cast<const Pod&>(p)) { }
00093
00094 template<typename Key> inline void operator() ()
00095 {
00096 typedef typename pcl::traits::datatype<PointT, Key>::type T;
00097 const uint8_t* raw_ptr = reinterpret_cast<const uint8_t*>(&p_) + pcl::traits::offset<PointT, Key>::value;
00098 const T* data_ptr = reinterpret_cast<const T*>(raw_ptr);
00099
00100
00101 if (!pcl_isfinite (*data_ptr))
00102 {
00103 f_idx_++;
00104 return;
00105 }
00106
00107 centroid_[f_idx_++] += *data_ptr;
00108 }
00109
00110 private:
00111 int f_idx_;
00112 Eigen::VectorXf ¢roid_;
00113 const Pod &p_;
00114 };
00115
00120 template <typename PointT> inline void
00121 computeNDCentroid (const pcl::PointCloud<PointT> &cloud, Eigen::VectorXf ¢roid);
00122
00128 template <typename PointT> inline void
00129 computeNDCentroid (const pcl::PointCloud<PointT> &cloud,
00130 const std::vector<int> &indices, Eigen::VectorXf ¢roid);
00131
00137 template <typename PointT> inline void
00138 computeNDCentroid (const pcl::PointCloud<PointT> &cloud,
00139 const pcl::PointIndices &indices, Eigen::VectorXf ¢roid);
00140
00150 template <typename PointT> inline void
00151 computeCovarianceMatrix (const pcl::PointCloud<PointT> &cloud,
00152 const Eigen::Vector4f ¢roid,
00153 Eigen::Matrix3f &covariance_matrix);
00154
00162 template <typename PointT> inline void
00163 computeCovarianceMatrixNormalized (const pcl::PointCloud<PointT> &cloud,
00164 const Eigen::Vector4f ¢roid,
00165 Eigen::Matrix3f &covariance_matrix);
00166
00177 template <typename PointT> inline void
00178 computeCovarianceMatrix (const pcl::PointCloud<PointT> &cloud,
00179 const std::vector<int> &indices,
00180 const Eigen::Vector4f ¢roid,
00181 Eigen::Matrix3f &covariance_matrix);
00182
00193 template <typename PointT> inline void
00194 computeCovarianceMatrix (const pcl::PointCloud<PointT> &cloud,
00195 const pcl::PointIndices &indices,
00196 const Eigen::Vector4f ¢roid,
00197 Eigen::Matrix3f &covariance_matrix);
00198
00207 template <typename PointT> inline void
00208 computeCovarianceMatrixNormalized (const pcl::PointCloud<PointT> &cloud,
00209 const std::vector<int> &indices,
00210 const Eigen::Vector4f ¢roid,
00211 Eigen::Matrix3f &covariance_matrix);
00212
00221 template <typename PointT> inline void
00222 computeCovarianceMatrixNormalized (const pcl::PointCloud<PointT> &cloud,
00223 const pcl::PointIndices &indices,
00224 const Eigen::Vector4f ¢roid,
00225 Eigen::Matrix3f &covariance_matrix);
00226
00237 inline void
00238 solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix,
00239 const Eigen::Vector4f &point,
00240 Eigen::Vector4f &plane_parameters, float &curvature);
00241
00253 inline void
00254 solvePlaneParameters (const Eigen::Matrix3f &covariance_matrix,
00255 float &nx, float &ny, float &nz, float &curvature);
00256
00260
00264 template <typename PointInT, typename PointOutT>
00265 class Feature : public PCLBase<PointInT>
00266 {
00267 using PCLBase<PointInT>::initCompute;
00268 using PCLBase<PointInT>::deinitCompute;
00269
00270 public:
00271 using PCLBase<PointInT>::indices_;
00272 using PCLBase<PointInT>::input_;
00273
00274 typedef PCLBase<PointInT> BaseClass;
00275
00276 typedef typename pcl::KdTree<PointInT> KdTree;
00277 typedef typename pcl::KdTree<PointInT>::Ptr KdTreePtr;
00278
00279 typedef pcl::PointCloud<PointInT> PointCloudIn;
00280 typedef typename PointCloudIn::Ptr PointCloudInPtr;
00281 typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00282
00283 typedef pcl::PointCloud<PointOutT> PointCloudOut;
00284
00285 typedef boost::function<int (int, double, std::vector<int> &, std::vector<float> &)> SearchMethod;
00286 typedef boost::function<int (const PointCloudIn &cloud, int index, double, std::vector<int> &, std::vector<float> &)> SearchMethodSurface;
00287
00288 public:
00290 Feature () : surface_(), tree_(), search_parameter_(0), search_radius_(0), k_(0), fake_surface_(false)
00291 {};
00292
00296 inline void
00297 setSearchSurface (const PointCloudInConstPtr &cloud)
00298 {
00299 surface_ = cloud;
00300 fake_surface_ = false;
00301
00302 }
00303
00305 inline PointCloudInConstPtr getSearchSurface () { return (surface_); }
00306
00310 inline void setSearchMethod (const KdTreePtr &tree) { tree_ = tree; }
00311
00313 inline KdTreePtr getSearchMethod () { return (tree_); }
00314
00316 inline double getSearchParameter () { return (search_parameter_); }
00317
00321 inline void setKSearch (int k) { k_ = k; }
00322
00324 inline int getKSearch () { return (k_); }
00325
00330 inline void setRadiusSearch (double radius) { search_radius_ = radius; }
00331
00333 inline double getRadiusSearch () { return (search_radius_); }
00334
00340 void compute (PointCloudOut &output);
00341
00350 inline int
00351 searchForNeighbors (int index, double parameter,
00352 std::vector<int> &indices, std::vector<float> &distances)
00353 {
00354 if (surface_ == input_)
00355 return (search_method_ (index, parameter, indices, distances));
00356 else
00357 return (search_method_surface_ (*input_, index, parameter, indices, distances));
00358 }
00359
00360 protected:
00362 std::string feature_name_;
00363
00365 SearchMethod search_method_;
00366
00368 SearchMethodSurface search_method_surface_;
00369
00373 PointCloudInConstPtr surface_;
00374
00376 KdTreePtr tree_;
00377
00379 double search_parameter_;
00380
00382 double search_radius_;
00383
00385 int k_;
00386
00388 inline const std::string& getClassName () const { return (feature_name_); }
00389
00390 private:
00392 bool fake_surface_;
00393
00395 virtual void computeFeature (PointCloudOut &output) = 0;
00396 public:
00397 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00398 };
00399
00400
00404 template <typename PointInT, typename PointNT, typename PointOutT>
00405 class FeatureFromNormals : public Feature<PointInT, PointOutT>
00406 {
00407 typedef typename Feature<PointInT, PointOutT>::PointCloudIn PointCloudIn;
00408 typedef typename PointCloudIn::Ptr PointCloudInPtr;
00409 typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00410
00411 typedef typename pcl::PointCloud<PointNT> PointCloudN;
00412 typedef typename PointCloudN::Ptr PointCloudNPtr;
00413 typedef typename PointCloudN::ConstPtr PointCloudNConstPtr;
00414
00415 typedef typename Feature<PointInT, PointOutT>::PointCloudOut PointCloudOut;
00416
00417 public:
00418
00419 using Feature<PointInT, PointOutT>::input_;
00420
00422 FeatureFromNormals () {};
00423
00428 inline void setInputNormals (const PointCloudNConstPtr &normals) { normals_ = normals; }
00429
00431 inline PointCloudNConstPtr getInputNormals () { return (normals_); }
00432
00433 protected:
00437 PointCloudNConstPtr normals_;
00438 public:
00439 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00440 };
00441 }
00442
00443 #include "pcl/features/feature.hpp"
00444
00445 #endif //#ifndef PCL_FEATURE_H_