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_MLS_H_
00039 #define PCL_MLS_H_
00040
00041
00042 #include <pcl/pcl_base.h>
00043 #include "pcl/features/normal_3d.h"
00044
00045 #include <Eigen/SVD>
00046
00047 namespace pcl
00048 {
00050
00054 template <typename PointInT, typename NormalOutT>
00055 class MovingLeastSquares : public PCLBase<PointInT>
00056 {
00057 using PCLBase<PointInT>::input_;
00058 using PCLBase<PointInT>::indices_;
00059 using PCLBase<PointInT>::initCompute;
00060 using PCLBase<PointInT>::deinitCompute;
00061
00062 public:
00063 typedef typename pcl::KdTree<PointInT> KdTree;
00064 typedef typename pcl::KdTree<PointInT>::Ptr KdTreePtr;
00065
00066 typedef pcl::PointCloud<NormalOutT> NormalCloudOut;
00067 typedef typename NormalCloudOut::Ptr NormalCloudOutPtr;
00068 typedef typename NormalCloudOut::ConstPtr NormalCloudOutConstPtr;
00069
00070 typedef pcl::PointCloud<PointInT> PointCloudIn;
00071 typedef typename PointCloudIn::Ptr PointCloudInPtr;
00072 typedef typename PointCloudIn::ConstPtr PointCloudInConstPtr;
00073
00074 typedef boost::function<int (int, double, std::vector<int> &, std::vector<float> &)> SearchMethod;
00075
00077 MovingLeastSquares () : tree_ (), order_ (2), polynomial_fit_ (true), search_radius_ (0), sqr_gauss_param_ (0) {};
00078
00083 inline void setOutputNormals (NormalCloudOutPtr cloud) { normals_ = cloud; }
00084
00086 inline NormalCloudOutPtr getOutputNormals () { return normals_; }
00087
00091 inline void
00092 setSearchMethod (const KdTreePtr &tree)
00093 {
00094 tree_ = tree;
00095
00096 int (KdTree::*radiusSearch)(int index, double radius, std::vector<int> &k_indices, std::vector<float> &k_sqr_distances, int max_nn) const = &KdTree::radiusSearch;
00097 search_method_ = boost::bind (radiusSearch, boost::ref (tree_), _1, _2, _3, _4, INT_MAX);
00098 }
00099
00101 inline KdTreePtr getSearchMethod () { return (tree_); }
00102
00106 inline void setPolynomialOrder (int order) { order_ = order; }
00107
00109 inline int getPolynomialOrder () { return (order_); }
00110
00114 inline void setPolynomialFit (bool polynomial_fit) { polynomial_fit_ = polynomial_fit; }
00115
00117 inline bool getPolynomialFit () { return (polynomial_fit_); }
00118
00123 inline void setSearchRadius (double radius) { search_radius_ = radius; sqr_gauss_param_ = search_radius_ * search_radius_; }
00124
00126 inline double getSearchRadius () { return (search_radius_); }
00127
00132 inline void setSqrGaussParam (double sqr_gauss_param) { sqr_gauss_param_ = sqr_gauss_param; }
00133
00135 inline double getSqrGaussParam () { return (sqr_gauss_param_); }
00136
00140 void reconstruct (PointCloudIn &output);
00141
00142 protected:
00144 NormalCloudOutPtr normals_;
00145
00147 SearchMethod search_method_;
00148
00150 KdTreePtr tree_;
00151
00153 int order_;
00154
00156 bool polynomial_fit_;
00157
00159 double search_radius_;
00160
00162 double sqr_gauss_param_;
00163
00169 inline int
00170 searchForNeighbors (int index, std::vector<int> &indices, std::vector<float> &sqr_distances)
00171 {
00172 return (search_method_ (index, search_radius_, indices, sqr_distances));
00173 }
00174
00175 private:
00177 int nr_coeff_;
00178
00180 void performReconstruction (PointCloudIn &output);
00181
00183 std::string getClassName () const { return ("MovingLeastSquares"); }
00184 };
00185 }
00186
00187 #endif //#ifndef PCL_MLS_H_