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_SURFACE_RECONSTRUCTION_H_
00039 #define PCL_SURFACE_RECONSTRUCTION_H_
00040
00041 #include <pcl/pcl_base.h>
00042 #include <pcl/PolygonMesh.h>
00043 #include <pcl/kdtree/kdtree.h>
00044 #include <pcl/ros/conversions.h>
00045 #include <boost/bind.hpp>
00046 #include <boost/function.hpp>
00047
00048 namespace pcl
00049 {
00053 template <typename PointInT>
00054 class SurfaceReconstruction: public PCLBase<PointInT>
00055 {
00056 public:
00057 using PCLBase<PointInT>::input_;
00058 using PCLBase<PointInT>::indices_;
00059 using PCLBase<PointInT>::initCompute;
00060 using PCLBase<PointInT>::deinitCompute;
00061
00062 typedef typename pcl::KdTree<PointInT> KdTree;
00063 typedef typename pcl::KdTree<PointInT>::Ptr KdTreePtr;
00064
00065 typedef boost::function<int (int, double, std::vector<int> &, std::vector<float> &)> SearchMethod;
00066
00068 SurfaceReconstruction () : tree_() {}
00069
00074 void reconstruct (pcl::PolygonMesh &output);
00075
00079 inline void
00080 setSearchMethod (const KdTreePtr &tree)
00081 {
00082 tree_ = tree;
00083
00084 int (KdTree::*nearestKSearch)(int index, int k, std::vector<int> &k_indices, std::vector<float> &k_distances) = &KdTree::nearestKSearch;
00085 search_method_ = boost::bind (nearestKSearch, boost::ref (tree_), _1, _2, _3, _4);
00086 }
00087
00089 inline KdTreePtr getSearchMethod () { return (tree_); }
00090
00091 protected:
00093 SearchMethod search_method_;
00094
00096 KdTreePtr tree_;
00097
00099 virtual void performReconstruction (pcl::PolygonMesh &output) = 0;
00100
00102 virtual std::string getClassName () const { return (""); }
00103 };
00104 }
00105
00106 #include "pcl/surface/impl/reconstruction.hpp"
00107
00108 #endif // PCL_SURFACE_RECONSTRUCTION_H_
00109