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_IMPL_ORGANIZED_DATA_INDEX_H_
00039 #define PCL_KDTREE_KDTREE_IMPL_ORGANIZED_DATA_INDEX_H_
00040
00041 #include "pcl/point_cloud.h"
00042 #include "pcl/kdtree/organized_data.h"
00043
00045 template <typename PointT> int
00046 pcl::OrganizedDataIndex<PointT>::radiusSearch (
00047 const PointCloud &cloud, int index, double radius, std::vector<int> &k_indices,
00048 std::vector<float> &k_distances, int max_nn) const
00049 {
00050 k_indices.clear ();
00051 k_distances.clear ();
00052
00053 if (cloud.height == 1)
00054 {
00055 ROS_ERROR ("[pcl::%s::nearestKSearch] Input dataset is not organized!", getName ().c_str ());
00056 return 0;
00057 }
00058 int data_size = cloud.points.size ();
00059 if (index >= data_size)
00060 return 0;
00061
00062
00063 int width = cloud.width,
00064 height = cloud.height;
00065
00066 int y=index/width, x=index-y*width;
00067
00068 const std::vector<PointT, Eigen::aligned_allocator<PointT> >& points = cloud.points;
00069 const PointT& point = points[index];
00070 if (!pcl_isfinite(point.x))
00071 return 0;
00072
00073
00074 k_indices.push_back(index);
00075 k_distances.push_back(0.0f);
00076
00077 float max_dist_squared = radius*radius;
00078 bool still_in_range = true,
00079 done = false;
00080 for (int radius=1; !done; ++radius)
00081 {
00082 int x2=x-radius-1, y2=y-radius;
00083 still_in_range = false;
00084 for (int i=0; i<8*radius; ++i)
00085 {
00086 if (i<=2*radius) ++x2; else if (i<=4*radius) ++y2; else if (i<=6*radius) --x2; else --y2;
00087 if (x2<0 || x2>=width || y2<0 || y2>=height)
00088 continue;
00089 int neighbor_index = y2*width + x2;
00090 const PointT& neighbor = points[neighbor_index];
00091 if (!pcl_isfinite(neighbor.x))
00092 continue;
00093 float distance_squared = squaredEuclideanDistance(point, neighbor);
00094 if (distance_squared > max_dist_squared)
00095 continue;
00096
00097 still_in_range = true;
00098 k_indices.push_back(neighbor_index);
00099 k_distances.push_back(distance_squared);
00100 if ((int)k_indices.size() >= max_nn)
00101 {
00102 done = true;
00103 break;
00104 }
00105 }
00106 if (!still_in_range)
00107 done = true;
00108 }
00109
00110 return (int(k_indices.size ()));
00111 }
00112
00114 template <typename PointT> int
00115 pcl::OrganizedDataIndex<PointT>::nearestKSearch (const PointCloud &cloud, int index, int k,
00116 std::vector<int> &k_indices, std::vector<float> &k_distances)
00117 {
00118 k_indices.resize (k);
00119 if (cloud.height == 1)
00120 {
00121 ROS_ERROR ("[pcl::%s::nearestKSearch] Input dataset is not dense!", getName ().c_str ());
00122 return 0;
00123 }
00124 int data_size = cloud.points.size ();
00125 if (index >= data_size)
00126 return 0;
00127
00128
00129 int width = cloud.width;
00130
00131
00132 int u = index / width;
00133 int v = index % width;
00134
00135 int l = -1, idx, uwv = u * width + v, uwvx;
00136
00137
00138 k_indices[++l] = index;
00139
00140 if (horizontal_window_==0 || vertical_window_)
00141 setSearchWindowAsK (k);
00142
00143
00144 for (int x = -horizontal_window_; x != horizontal_window_; ++x)
00145 {
00146 uwvx = uwv + x * width;
00147
00148 for (int y = -vertical_window_; y != vertical_window_; ++y)
00149 {
00150
00151 idx = uwvx + y;
00152
00153
00154 if (idx == index || idx < 0 || idx >= data_size)
00155 continue;
00156
00157 if (max_distance_ != 0)
00158 {
00159 if (fabs (cloud.points[index].z - cloud.points[idx].z) < max_distance_)
00160 k_indices[++l] = idx;
00161 }
00162 else
00163 k_indices[++l] = idx;
00164 }
00165 }
00166
00167 if (l < min_pts_)
00168 return 0;
00169 return k;
00170 }
00171
00173 template <typename PointT> void
00174 pcl::OrganizedDataIndex<PointT>::setSearchWindowAsK (int k)
00175 {
00176 int hw = 0, vw = 0;
00177 while ( (2 * hw + 1 ) * (2 * vw + 1) < k)
00178 {
00179 ++hw; ++vw;
00180 }
00181 horizontal_window_ = hw - 1;
00182 vertical_window_ = vw - 1;
00183 }
00184
00185 #define PCL_INSTANTIATE_OrganizedDataIndex(T) template class pcl::OrganizedDataIndex<T>;
00186
00187 #endif //#ifndef _PCL_KDTREE_KDTREE_IMPL_ORGANIZED_DATA_INDEX_H_
00188