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 #ifndef __NABO_PRIVATE_H
00033 #define __NABO_PRIVATE_H
00034
00035 #include "nabo.h"
00036
00037 #include <cstdint>
00038 using std::uint32_t;
00039
00040
00041 #ifdef HAVE_OPENCL
00042 #define __CL_ENABLE_EXCEPTIONS
00043 #include "CL/cl.hpp"
00044 #endif // HAVE_OPENCL
00045
00046
00047 #if defined(__GNUC__)
00048 #define _UNUSED __attribute__ ((unused))
00049 #else
00050 #define _UNUSED
00051 #endif
00052
00058 namespace Nabo
00059 {
00061
00062
00064 template<typename T, typename A, typename B>
00065 inline T dist2(const A& v0, const B& v1)
00066 {
00067 return (v0 - v1).squaredNorm();
00068 }
00069
00071 template<typename T, typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> >
00072 struct BruteForceSearch : public NearestNeighbourSearch<T, CloudType>
00073 {
00074 typedef typename NearestNeighbourSearch<T, CloudType>::Vector Vector;
00075 typedef typename NearestNeighbourSearch<T, CloudType>::Matrix Matrix;
00076 typedef typename NearestNeighbourSearch<T, CloudType>::Index Index;
00077 typedef typename NearestNeighbourSearch<T, CloudType>::IndexVector IndexVector;
00078 typedef typename NearestNeighbourSearch<T, CloudType>::IndexMatrix IndexMatrix;
00079
00080 using NearestNeighbourSearch<T, CloudType>::dim;
00081 using NearestNeighbourSearch<T, CloudType>::creationOptionFlags;
00082 using NearestNeighbourSearch<T, CloudType>::checkSizesKnn;
00083 using NearestNeighbourSearch<T, CloudType>::minBound;
00084 using NearestNeighbourSearch<T, CloudType>::maxBound;
00085
00087 BruteForceSearch(const CloudType& cloud, const Index dim, const unsigned creationOptionFlags);
00088 virtual unsigned long knn(const Matrix& query, IndexMatrix& indices, Matrix& dists2, const Index k, const T epsilon, const unsigned optionFlags, const T maxRadius) const;
00089 virtual unsigned long knn(const Matrix& query, IndexMatrix& indices, Matrix& dists2, const Vector& maxRadii, const Index k = 1, const T epsilon = 0, const unsigned optionFlags = 0) const;
00090 };
00091
00093 template<typename T, typename Heap, typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> >
00094 struct KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt: public NearestNeighbourSearch<T, CloudType>
00095 {
00096 typedef typename NearestNeighbourSearch<T, CloudType>::Vector Vector;
00097 typedef typename NearestNeighbourSearch<T, CloudType>::Matrix Matrix;
00098 typedef typename NearestNeighbourSearch<T, CloudType>::Index Index;
00099 typedef typename NearestNeighbourSearch<T, CloudType>::IndexVector IndexVector;
00100 typedef typename NearestNeighbourSearch<T, CloudType>::IndexMatrix IndexMatrix;
00101
00102 using NearestNeighbourSearch<T, CloudType>::dim;
00103 using NearestNeighbourSearch<T, CloudType>::cloud;
00104 using NearestNeighbourSearch<T, CloudType>::creationOptionFlags;
00105 using NearestNeighbourSearch<T, CloudType>::minBound;
00106 using NearestNeighbourSearch<T, CloudType>::maxBound;
00107 using NearestNeighbourSearch<T, CloudType>::checkSizesKnn;
00108
00109 protected:
00111 typedef std::vector<Index> BuildPoints;
00113 typedef typename BuildPoints::iterator BuildPointsIt;
00115 typedef typename BuildPoints::const_iterator BuildPointsCstIt;
00116
00118 const unsigned bucketSize;
00119
00121 const uint32_t dimBitCount;
00123 const uint32_t dimMask;
00124
00126 inline uint32_t createDimChildBucketSize(const uint32_t dim, const uint32_t childIndex) const
00127 { return dim | (childIndex << dimBitCount); }
00129 inline uint32_t getDim(const uint32_t dimChildBucketSize) const
00130 { return dimChildBucketSize & dimMask; }
00132 inline uint32_t getChildBucketSize(const uint32_t dimChildBucketSize) const
00133 { return dimChildBucketSize >> dimBitCount; }
00134
00135 struct BucketEntry;
00136
00138 struct Node
00139 {
00140 uint32_t dimChildBucketSize;
00141 union
00142 {
00143 T cutVal;
00144 uint32_t bucketIndex;
00145 };
00146
00148 Node(const uint32_t dimChild, const T cutVal):
00149 dimChildBucketSize(dimChild), cutVal(cutVal) {}
00151 Node(const uint32_t bucketSize, const uint32_t bucketIndex):
00152 dimChildBucketSize(bucketSize), bucketIndex(bucketIndex) {}
00153 };
00155 typedef std::vector<Node> Nodes;
00156
00158 struct BucketEntry
00159 {
00160 const T* pt;
00161 Index index;
00162
00164
00167 BucketEntry(const T* pt = 0, const Index index = 0): pt(pt), index(index) {}
00168 };
00169
00171 typedef std::vector<BucketEntry> Buckets;
00172
00174 Nodes nodes;
00175
00177 Buckets buckets;
00178
00180 std::pair<T,T> getBounds(const BuildPointsIt first, const BuildPointsIt last, const unsigned dim);
00182 unsigned buildNodes(const BuildPointsIt first, const BuildPointsIt last, const Vector minValues, const Vector maxValues);
00183
00185
00197 unsigned long onePointKnn(const Matrix& query, IndexMatrix& indices, Matrix& dists2, int i, Heap& heap, std::vector<T>& off, const T maxError, const T maxRadius2, const bool allowSelfMatch, const bool collectStatistics, const bool sortResults) const;
00198
00200
00208 template<bool allowSelfMatch, bool collectStatistics>
00209 unsigned long recurseKnn(const T* query, const unsigned n, T rd, Heap& heap, std::vector<T>& off, const T maxError, const T maxRadius2) const;
00210
00211 public:
00213 KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt(const CloudType& cloud, const Index dim, const unsigned creationOptionFlags, const Parameters& additionalParameters);
00214 virtual unsigned long knn(const Matrix& query, IndexMatrix& indices, Matrix& dists2, const Index k, const T epsilon, const unsigned optionFlags, const T maxRadius) const;
00215 virtual unsigned long knn(const Matrix& query, IndexMatrix& indices, Matrix& dists2, const Vector& maxRadii, const Index k = 1, const T epsilon = 0, const unsigned optionFlags = 0) const;
00216 };
00217
00218 #ifdef HAVE_OPENCL
00219
00221 template<typename T, typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> >
00222 struct OpenCLSearch: public NearestNeighbourSearch<T, CloudType>
00223 {
00224 typedef typename NearestNeighbourSearch<T, CloudType>::Vector Vector;
00225 typedef typename NearestNeighbourSearch<T, CloudType>::Matrix Matrix;
00226 typedef typename NearestNeighbourSearch<T, CloudType>::Index Index;
00227 typedef typename NearestNeighbourSearch<T, CloudType>::IndexVector IndexVector;
00228 typedef typename NearestNeighbourSearch<T, CloudType>::IndexMatrix IndexMatrix;
00229
00230 using NearestNeighbourSearch<T, CloudType>::dim;
00231 using NearestNeighbourSearch<T, CloudType>::cloud;
00232 using NearestNeighbourSearch<T, CloudType>::creationOptionFlags;
00233 using NearestNeighbourSearch<T, CloudType>::checkSizesKnn;
00234
00235 protected:
00236 const cl_device_type deviceType;
00237 cl::Context& context;
00238 mutable cl::Kernel knnKernel;
00239 cl::CommandQueue queue;
00240 cl::Buffer cloudCL;
00241
00243 OpenCLSearch(const CloudType& cloud, const Index dim, const unsigned creationOptionFlags, const cl_device_type deviceType);
00245
00249 void initOpenCL(const char* clFileName, const char* kernelName, const std::string& additionalDefines = "");
00250
00251 public:
00252 virtual unsigned long knn(const Matrix& query, IndexMatrix& indices, Matrix& dists2, const Index k, const T epsilon, const unsigned optionFlags, const T maxRadius) const;
00253 virtual unsigned long knn(const Matrix& query, IndexMatrix& indices, Matrix& dists2, const Vector& maxRadii, const Index k = 1, const T epsilon = 0, const unsigned optionFlags = 0) const;
00254 };
00255
00257 template<typename T, typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> >
00258 struct BruteForceSearchOpenCL: public OpenCLSearch<T, CloudType>
00259 {
00260 typedef typename NearestNeighbourSearch<T, CloudType>::Vector Vector;
00261 typedef typename NearestNeighbourSearch<T, CloudType>::Matrix Matrix;
00262 typedef typename NearestNeighbourSearch<T, CloudType>::Index Index;
00263
00264 using OpenCLSearch<T, CloudType>::initOpenCL;
00265
00267 BruteForceSearchOpenCL(const CloudType& cloud, const Index dim, const unsigned creationOptionFlags, const cl_device_type deviceType);
00268 };
00269
00271 template<typename T, typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> >
00272 struct KDTreeBalancedPtInLeavesStackOpenCL: public OpenCLSearch<T, CloudType>
00273 {
00274 typedef typename NearestNeighbourSearch<T, CloudType>::Vector Vector;
00275 typedef typename NearestNeighbourSearch<T, CloudType>::Matrix Matrix;
00276 typedef typename NearestNeighbourSearch<T, CloudType>::Index Index;
00277 typedef typename NearestNeighbourSearch<T, CloudType>::IndexVector IndexVector;
00278 typedef typename NearestNeighbourSearch<T, CloudType>::IndexMatrix IndexMatrix;
00279
00280 using NearestNeighbourSearch<T, CloudType>::dim;
00281 using NearestNeighbourSearch<T, CloudType>::cloud;
00282 using NearestNeighbourSearch<T, CloudType>::creationOptionFlags;
00283 using NearestNeighbourSearch<T, CloudType>::minBound;
00284 using NearestNeighbourSearch<T, CloudType>::maxBound;
00285
00286 using OpenCLSearch<T, CloudType>::context;
00287 using OpenCLSearch<T, CloudType>::knnKernel;
00288
00289 using OpenCLSearch<T, CloudType>::initOpenCL;
00290
00291 protected:
00293 struct BuildPoint
00294 {
00295 Vector pos;
00296 size_t index;
00297
00298 BuildPoint(const Vector& pos = Vector(), const size_t index = 0): pos(pos), index(index) {}
00299 };
00301 typedef std::vector<BuildPoint> BuildPoints;
00303 typedef typename BuildPoints::iterator BuildPointsIt;
00305 typedef typename BuildPoints::const_iterator BuildPointsCstIt;
00306
00308 struct CompareDim
00309 {
00310 size_t dim;
00311
00312 CompareDim(const size_t dim):dim(dim){}
00314 bool operator() (const BuildPoint& p0, const BuildPoint& p1) { return p0.pos(dim) < p1.pos(dim); }
00315 };
00316
00318 struct Node
00319 {
00320 int dim;
00321 T cutVal;
00322
00323 Node(const int dim = -1, const T cutVal = 0):dim(dim), cutVal(cutVal) {}
00324 };
00326 typedef std::vector<Node> Nodes;
00327
00328 Nodes nodes;
00329 cl::Buffer nodesCL;
00330
00331
00332 inline size_t childLeft(size_t pos) const { return 2*pos + 1; }
00333 inline size_t childRight(size_t pos) const { return 2*pos + 2; }
00334 inline size_t parent(size_t pos) const { return (pos-1)/2; }
00335 size_t getTreeDepth(size_t size) const;
00336 size_t getTreeSize(size_t size) const;
00337
00339 void buildNodes(const BuildPointsIt first, const BuildPointsIt last, const size_t pos, const Vector minValues, const Vector maxValues);
00340
00341 public:
00343 KDTreeBalancedPtInLeavesStackOpenCL(const CloudType& cloud, const Index dim, const unsigned creationOptionFlags, const cl_device_type deviceType);
00344 };
00345
00347 template<typename T, typename CloudType = Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> >
00348 struct KDTreeBalancedPtInNodesStackOpenCL: public OpenCLSearch<T, CloudType>
00349 {
00350 typedef typename NearestNeighbourSearch<T, CloudType>::Vector Vector;
00351 typedef typename NearestNeighbourSearch<T, CloudType>::Matrix Matrix;
00352 typedef typename NearestNeighbourSearch<T, CloudType>::Index Index;
00353 typedef typename NearestNeighbourSearch<T, CloudType>::IndexVector IndexVector;
00354 typedef typename NearestNeighbourSearch<T, CloudType>::IndexMatrix IndexMatrix;
00355
00356 using NearestNeighbourSearch<T, CloudType>::dim;
00357 using NearestNeighbourSearch<T, CloudType>::cloud;
00358 using NearestNeighbourSearch<T, CloudType>::creationOptionFlags;
00359 using NearestNeighbourSearch<T, CloudType>::minBound;
00360 using NearestNeighbourSearch<T, CloudType>::maxBound;
00361
00362 using OpenCLSearch<T, CloudType>::context;
00363 using OpenCLSearch<T, CloudType>::knnKernel;
00364
00365 using OpenCLSearch<T, CloudType>::initOpenCL;
00366
00367 protected:
00369 typedef Index BuildPoint;
00371 typedef std::vector<BuildPoint> BuildPoints;
00373 typedef typename BuildPoints::iterator BuildPointsIt;
00375 typedef typename BuildPoints::const_iterator BuildPointsCstIt;
00376
00378 struct CompareDim
00379 {
00380 const CloudType& cloud;
00381 size_t dim;
00382
00383 CompareDim(const CloudType& cloud, const size_t dim): cloud(cloud), dim(dim){}
00385 bool operator() (const BuildPoint& p0, const BuildPoint& p1) { return cloud.coeff(dim, p0) < cloud.coeff(dim, p1); }
00386 };
00387
00389 struct Node
00390 {
00391 int dim;
00392 Index index;
00393
00394 Node(const int dim = -2, const Index index = 0):dim(dim), index(index) {}
00395 };
00397 typedef std::vector<Node> Nodes;
00398
00399 Nodes nodes;
00400 cl::Buffer nodesCL;
00401
00402
00403 inline size_t childLeft(size_t pos) const { return 2*pos + 1; }
00404 inline size_t childRight(size_t pos) const { return 2*pos + 2; }
00405 inline size_t parent(size_t pos) const { return (pos-1)/2; }
00406 size_t getTreeDepth(size_t size) const;
00407 size_t getTreeSize(size_t size) const;
00408
00410 void buildNodes(const BuildPointsIt first, const BuildPointsIt last, const size_t pos, const Vector minValues, const Vector maxValues);
00411
00412 public:
00414 KDTreeBalancedPtInNodesStackOpenCL(const CloudType& cloud, const Index dim, const unsigned creationOptionFlags, const cl_device_type deviceType);
00415 };
00416
00417 #endif // HAVE_OPENCL
00418
00420 }
00421
00422 #endif // __NABO_H