Go to the documentation of this file.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 #ifndef PCL_SEARCH_KDTREE_H_
00040 #define PCL_SEARCH_KDTREE_H_
00041
00042 #include <pcl/search/search.h>
00043 #include <pcl/kdtree/kdtree.h>
00044 #include <pcl/kdtree/kdtree_flann.h>
00045
00046 namespace pcl
00047 {
00048 namespace search
00049 {
00058 template<typename PointT>
00059 class KdTree: public Search<PointT>
00060 {
00061 public:
00062 typedef typename Search<PointT>::PointCloud PointCloud;
00063 typedef typename Search<PointT>::PointCloudConstPtr PointCloudConstPtr;
00064
00065 typedef boost::shared_ptr<std::vector<int> > IndicesPtr;
00066 typedef boost::shared_ptr<const std::vector<int> > IndicesConstPtr;
00067
00068 using pcl::search::Search<PointT>::indices_;
00069 using pcl::search::Search<PointT>::input_;
00070 using pcl::search::Search<PointT>::getIndices;
00071 using pcl::search::Search<PointT>::getInputCloud;
00072 using pcl::search::Search<PointT>::nearestKSearch;
00073 using pcl::search::Search<PointT>::radiusSearch;
00074 using pcl::search::Search<PointT>::sorted_results_;
00075
00076 typedef boost::shared_ptr<KdTree<PointT> > Ptr;
00077 typedef boost::shared_ptr<const KdTree<PointT> > ConstPtr;
00078
00079 typedef boost::shared_ptr<pcl::KdTreeFLANN<PointT> > KdTreeFLANNPtr;
00080 typedef boost::shared_ptr<const pcl::KdTreeFLANN<PointT> > KdTreeFLANNConstPtr;
00081
00089 KdTree (bool sorted = true)
00090 : Search<PointT> ("KdTree", sorted)
00091 , tree_ (new pcl::KdTreeFLANN<PointT> (sorted))
00092 {
00093 }
00094
00096 virtual
00097 ~KdTree ()
00098 {
00099 }
00100
00104 virtual void
00105 setSortedResults (bool sorted_results)
00106 {
00107 sorted_results_ = sorted_results;
00108 tree_->setSortedResults (sorted_results);
00109 }
00110
00114 inline void
00115 setEpsilon (float eps)
00116 {
00117 tree_->setEpsilon (eps);
00118 }
00119
00121 inline float
00122 getEpsilon () const
00123 {
00124 return (tree_->getEpsilon ());
00125 }
00126
00131 inline void
00132 setInputCloud (const PointCloudConstPtr& cloud, const IndicesConstPtr& indices = IndicesConstPtr ())
00133 {
00134 tree_->setInputCloud (cloud, indices);
00135 input_ = cloud;
00136 indices_ = indices;
00137 }
00138
00147 inline int
00148 nearestKSearch (const PointT &point, int k, std::vector<int> &k_indices, std::vector<float> &k_sqr_distances) const
00149 {
00150 return (tree_->nearestKSearch (point, k, k_indices, k_sqr_distances));
00151 }
00152
00163 inline int
00164 radiusSearch (const PointT& point, double radius,
00165 std::vector<int> &k_indices, std::vector<float> &k_sqr_distances,
00166 unsigned int max_nn = 0) const
00167 {
00168 return (tree_->radiusSearch (point, radius, k_indices, k_sqr_distances, max_nn));
00169 }
00170
00171 protected:
00173 KdTreeFLANNPtr tree_;
00174 };
00175 }
00176 }
00177
00178 #define PCL_INSTANTIATE_KdTree(T) template class PCL_EXPORTS pcl::search::KdTree<T>;
00179
00180 #endif // PCL_SEARCH_KDTREE_H_
00181