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_KDTREE_KDTREE_H_
00039 #define PCL_KDTREE_KDTREE_H_
00040
00041 #include <limits.h>
00042 #include "pcl/ros_macros.h"
00043 #include "pcl/pcl_macros.h"
00044 #include "pcl/point_cloud.h"
00045 #include "pcl/point_representation.h"
00046 #include <boost/make_shared.hpp>
00047
00048 namespace pcl
00049 {
00051
00055 template <typename PointT>
00056 class KdTree
00057 {
00058 typedef boost::shared_ptr <std::vector<int> > IndicesPtr;
00059 typedef boost::shared_ptr <const std::vector<int> > IndicesConstPtr;
00060
00061 public:
00062 typedef pcl::PointCloud<PointT> PointCloud;
00063 typedef boost::shared_ptr<PointCloud> PointCloudPtr;
00064 typedef boost::shared_ptr<const PointCloud> PointCloudConstPtr;
00065
00066 typedef pcl::PointRepresentation<PointT> PointRepresentation;
00067
00068 typedef boost::shared_ptr<const PointRepresentation> PointRepresentationConstPtr;
00069
00070
00071 typedef boost::shared_ptr<KdTree<PointT> > Ptr;
00072 typedef boost::shared_ptr<const KdTree<PointT> > ConstPtr;
00073
00075 KdTree (bool sorted = true) : input_(), indices_(),
00076 epsilon_(0.0), min_pts_(1), sorted_(sorted)
00077 {
00078 point_representation_ = boost::make_shared<DefaultPointRepresentation<PointT> > ();
00079 };
00080
00081
00086 virtual inline void
00087 setInputCloud (const PointCloudConstPtr &cloud, const IndicesConstPtr &indices = IndicesConstPtr ())
00088 {
00089 input_ = cloud;
00090 indices_ = indices;
00091 }
00092
00094 inline IndicesConstPtr const
00095 getIndices ()
00096 {
00097 return (indices_);
00098 }
00099
00101 inline PointCloudConstPtr
00102 getInputCloud ()
00103 {
00104 return (input_);
00105 }
00106
00110 inline void
00111 setPointRepresentation (const PointRepresentationConstPtr &point_representation)
00112 {
00113 point_representation_ = point_representation;
00114 setInputCloud (input_, indices_);
00115 }
00116
00118 inline PointRepresentationConstPtr const
00119 getPointRepresentation ()
00120 {
00121 return (point_representation_);
00122 }
00123
00125 virtual ~KdTree () {};
00126
00136 virtual int
00137 nearestKSearch (const PointCloud &cloud, int index, int k, std::vector<int> &k_indices, std::vector<float> &k_sqr_distances) = 0;
00138
00147 virtual int
00148 nearestKSearch (const PointT &p_q, int k, std::vector<int> &k_indices, std::vector<float> &k_sqr_distances) = 0;
00149
00159 virtual int
00160 nearestKSearch (int index, int k, std::vector<int> &k_indices, std::vector<float> &k_sqr_distances) = 0;
00161
00171 virtual int
00172 radiusSearch (const PointCloud &cloud, int index, double radius, std::vector<int> &k_indices,
00173 std::vector<float> &k_sqr_distances, int max_nn = INT_MAX) const = 0;
00174
00183 virtual int
00184 radiusSearch (const PointT &p_q, double radius, std::vector<int> &k_indices,
00185 std::vector<float> &k_sqr_distances, int max_nn = INT_MAX) const = 0;
00186
00196 virtual int
00197 radiusSearch (int index, double radius, std::vector<int> &k_indices,
00198 std::vector<float> &k_sqr_distances, int max_nn = INT_MAX) const = 0;
00199
00203 inline void
00204 setEpsilon (double eps)
00205 {
00206 epsilon_ = eps;
00207 }
00208
00210 inline double
00211 getEpsilon ()
00212 {
00213 return (epsilon_);
00214 }
00215
00217 inline void
00218 setMinPts (int min_pts)
00219 {
00220 min_pts_ = min_pts;
00221 }
00222
00224 inline float
00225 getMinPts ()
00226 {
00227 return (min_pts_);
00228 }
00229
00230 protected:
00232 PointCloudConstPtr input_;
00233
00235 IndicesConstPtr indices_;
00236
00238 double epsilon_;
00239
00241 int min_pts_;
00242
00244 bool sorted_;
00245
00247 PointRepresentationConstPtr point_representation_;
00248
00250 virtual std::string
00251 getName () const = 0;
00252 };
00253 }
00254
00255 #endif //#ifndef _PCL_KDTREE_KDTREE_H_