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_ORGANIZED_DATA_H_
00039 #define PCL_KDTREE_ORGANIZED_DATA_H_
00040
00041 #include "pcl/kdtree/kdtree.h"
00042 #include <boost/shared_ptr.hpp>
00043 #include <boost/thread/mutex.hpp>
00044
00045 namespace pcl
00046 {
00048
00052 template <typename PointT>
00053 class OrganizedDataIndex : public KdTree<PointT>
00054 {
00055 using KdTree<PointT>::input_;
00056 using KdTree<PointT>::min_pts_;
00057
00058 typedef KdTree<PointT> BaseClass;
00059 typedef typename KdTree<PointT>::PointCloud PointCloud;
00060 typedef typename KdTree<PointT>::PointCloudConstPtr PointCloudConstPtr;
00061
00062 public:
00063
00064 typedef boost::shared_ptr<OrganizedDataIndex<PointT> > Ptr;
00065 typedef boost::shared_ptr<const OrganizedDataIndex<PointT> > ConstPtr;
00066
00068 OrganizedDataIndex () : KdTree<PointT>(), max_distance_ (0), horizontal_window_ (0), vertical_window_ (0) {}
00069
00070 inline Ptr makeShared () const { return Ptr (new OrganizedDataIndex<PointT> (*this)); }
00071
00072
00073 int nearestKSearch (const PointT &p_q, int k, std::vector<int> &k_indices, std::vector<float> &k_distances)
00074 {
00075 ROS_ERROR ("%s: Method not implemented!", __PRETTY_FUNCTION__); return (false);
00076 }
00077 int radiusSearch (const PointT &p_q, double radius, std::vector<int> &k_indices,
00078 std::vector<float> &k_distances, int max_nn = INT_MAX) const
00079 {
00080 ROS_ERROR ("%s: Method not implemented!", __PRETTY_FUNCTION__); return (false);
00081 }
00082
00091 int radiusSearch (const PointCloud &cloud, int index, double radius, std::vector<int> &k_indices,
00092 std::vector<float> &k_distances, int max_nn = INT_MAX) const;
00093
00101 inline int
00102 radiusSearch (int index, double radius, std::vector<int> &k_indices,
00103 std::vector<float> &k_distances, int max_nn = INT_MAX) const
00104 {
00105 if (!input_)
00106 {
00107 ROS_ERROR ("[%s] Input dataset does not exist or wrong input dataset!", __PRETTY_FUNCTION__);
00108 return (false);
00109 }
00110 return (radiusSearch (*input_, index, radius, k_indices, k_distances, max_nn));
00111 }
00112
00120 int nearestKSearch (const PointCloud &cloud, int index, int k, std::vector<int> &k_indices, std::vector<float> &k_distances);
00121
00128 inline int
00129 nearestKSearch (int index, int k, std::vector<int> &k_indices,
00130 std::vector<float> &k_distances)
00131 {
00132 if (!input_)
00133 {
00134 ROS_ERROR ("[pcl::%s::nearestKSearch] Input dataset does not exist or wrong input dataset!", getName ().c_str ());
00135 return 0;
00136 }
00137 return (nearestKSearch (*input_, index, k, k_indices, k_distances));
00138 }
00139
00144 inline void
00145 setSearchWindow (int horizontal, int vertical)
00146 {
00147 horizontal_window_ = horizontal;
00148 vertical_window_ = vertical;
00149 }
00150
00154 void setSearchWindowAsK (int k);
00155
00157 int getHorizontalSearchWindow () const { return (horizontal_window_); }
00158
00160 int getVerticalSearchWindow () const { return (vertical_window_); }
00161
00163 void setMaxDistance (float max_dist) { max_distance_ = max_dist; }
00164
00166
00167 float getMaxDistance () const { return (max_distance_); }
00168
00169 private:
00171
00172 virtual std::string getName () const { return ("OrganizedDataIndex"); }
00173
00175 float max_distance_;
00176
00178 int horizontal_window_;
00179
00181 int vertical_window_;
00182 };
00183 }
00184
00185 #endif //#ifndef _PCL_KDTREE_ORGANIZED_DATA_H_