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 #ifndef NANOFLANN_HPP_
00034 #define NANOFLANN_HPP_
00035
00036 #include <vector>
00037 #include <cassert>
00038 #include <algorithm>
00039 #include <stdexcept>
00040 #include <cstdio>
00041 #include <cmath>
00042 #include <limits>
00043
00044
00045 #if !defined(NOMINMAX) && (defined(_WIN32) || defined(_WIN32_) || defined(WIN32) || defined(_WIN64))
00046 # define NOMINMAX
00047 # ifdef max
00048 # undef max
00049 # undef min
00050 # endif
00051 #endif
00052
00053 namespace nanoflann
00054 {
00059 #define NANOFLANN_VERSION 0x118
00060
00063 template <typename DistanceType, typename IndexType = size_t, typename CountType = size_t>
00064 class KNNResultSet
00065 {
00066 IndexType * indices;
00067 DistanceType* dists;
00068 CountType capacity;
00069 CountType count;
00070
00071 public:
00072 inline KNNResultSet(CountType capacity_) : capacity(capacity_), count(0)
00073 {
00074 }
00075
00076 inline void init(IndexType* indices_, DistanceType* dists_)
00077 {
00078 indices = indices_;
00079 dists = dists_;
00080 count = 0;
00081 dists[capacity-1] = (std::numeric_limits<DistanceType>::max)();
00082 }
00083
00084 inline CountType size() const
00085 {
00086 return count;
00087 }
00088
00089 inline bool full() const
00090 {
00091 return count == capacity;
00092 }
00093
00094
00095 inline void addPoint(DistanceType dist, IndexType index)
00096 {
00097 CountType i;
00098 for (i=count; i>0; --i) {
00099 #ifdef NANOFLANN_FIRST_MATCH // If defined and two poins have the same distance, the one with the lowest-index will be returned first.
00100 if ( (dists[i-1]>dist) || ((dist==dists[i-1])&&(indices[i-1]>index)) ) {
00101 #else
00102 if (dists[i-1]>dist) {
00103 #endif
00104 if (i<capacity) {
00105 dists[i] = dists[i-1];
00106 indices[i] = indices[i-1];
00107 }
00108 }
00109 else break;
00110 }
00111 if (i<capacity) {
00112 dists[i] = dist;
00113 indices[i] = index;
00114 }
00115 if (count<capacity) count++;
00116 }
00117
00118 inline DistanceType worstDist() const
00119 {
00120 return dists[capacity-1];
00121 }
00122 };
00123
00124
00128 template <typename DistanceType, typename IndexType = size_t>
00129 class RadiusResultSet
00130 {
00131 public:
00132 const DistanceType radius;
00133
00134 std::vector<std::pair<IndexType,DistanceType> >& m_indices_dists;
00135
00136 inline RadiusResultSet(DistanceType radius_, std::vector<std::pair<IndexType,DistanceType> >& indices_dists) : radius(radius_), m_indices_dists(indices_dists)
00137 {
00138 init();
00139 }
00140
00141 inline ~RadiusResultSet() { }
00142
00143 inline void init() { clear(); }
00144 inline void clear() { m_indices_dists.clear(); }
00145
00146 inline size_t size() const { return m_indices_dists.size(); }
00147
00148 inline bool full() const { return true; }
00149
00150 inline void addPoint(DistanceType dist, IndexType index)
00151 {
00152 if (dist<radius)
00153 m_indices_dists.push_back(std::make_pair(index,dist));
00154 }
00155
00156 inline DistanceType worstDist() const { return radius; }
00157
00159 inline void set_radius_and_clear( const DistanceType r )
00160 {
00161 radius = r;
00162 clear();
00163 }
00164
00169 std::pair<IndexType,DistanceType> worst_item() const
00170 {
00171 if (m_indices_dists.empty()) throw std::runtime_error("Cannot invoke RadiusResultSet::worst_item() on an empty list of results.");
00172 typedef typename std::vector<std::pair<IndexType,DistanceType> >::const_iterator DistIt;
00173 DistIt it = std::max_element(m_indices_dists.begin(), m_indices_dists.end());
00174 return *it;
00175 }
00176 };
00177
00179 struct IndexDist_Sorter
00180 {
00182 template <typename PairType>
00183 inline bool operator()(const PairType &p1, const PairType &p2) const {
00184 return p1.second < p2.second;
00185 }
00186 };
00187
00193 template<typename T>
00194 void save_value(FILE* stream, const T& value, size_t count = 1)
00195 {
00196 fwrite(&value, sizeof(value),count, stream);
00197 }
00198
00199 template<typename T>
00200 void save_value(FILE* stream, const std::vector<T>& value)
00201 {
00202 size_t size = value.size();
00203 fwrite(&size, sizeof(size_t), 1, stream);
00204 fwrite(&value[0], sizeof(T), size, stream);
00205 }
00206
00207 template<typename T>
00208 void load_value(FILE* stream, T& value, size_t count = 1)
00209 {
00210 size_t read_cnt = fread(&value, sizeof(value), count, stream);
00211 if (read_cnt != count) {
00212 throw std::runtime_error("Cannot read from file");
00213 }
00214 }
00215
00216
00217 template<typename T>
00218 void load_value(FILE* stream, std::vector<T>& value)
00219 {
00220 size_t size;
00221 size_t read_cnt = fread(&size, sizeof(size_t), 1, stream);
00222 if (read_cnt!=1) {
00223 throw std::runtime_error("Cannot read from file");
00224 }
00225 value.resize(size);
00226 read_cnt = fread(&value[0], sizeof(T), size, stream);
00227 if (read_cnt!=size) {
00228 throw std::runtime_error("Cannot read from file");
00229 }
00230 }
00237 template<typename T> inline T abs(T x) { return (x<0) ? -x : x; }
00238 template<> inline int abs<int>(int x) { return ::abs(x); }
00239 template<> inline float abs<float>(float x) { return fabsf(x); }
00240 template<> inline double abs<double>(double x) { return fabs(x); }
00241 template<> inline long double abs<long double>(long double x) { return fabsl(x); }
00242
00248 template<class T, class DataSource, typename _DistanceType = T>
00249 struct L1_Adaptor
00250 {
00251 typedef T ElementType;
00252 typedef _DistanceType DistanceType;
00253
00254 const DataSource &data_source;
00255
00256 L1_Adaptor(const DataSource &_data_source) : data_source(_data_source) { }
00257
00258 inline DistanceType operator()(const T* a, const size_t b_idx, size_t size, DistanceType worst_dist = -1) const
00259 {
00260 DistanceType result = DistanceType();
00261 const T* last = a + size;
00262 const T* lastgroup = last - 3;
00263 size_t d = 0;
00264
00265
00266 while (a < lastgroup) {
00267 const DistanceType diff0 = nanoflann::abs(a[0] - data_source.kdtree_get_pt(b_idx,d++));
00268 const DistanceType diff1 = nanoflann::abs(a[1] - data_source.kdtree_get_pt(b_idx,d++));
00269 const DistanceType diff2 = nanoflann::abs(a[2] - data_source.kdtree_get_pt(b_idx,d++));
00270 const DistanceType diff3 = nanoflann::abs(a[3] - data_source.kdtree_get_pt(b_idx,d++));
00271 result += diff0 + diff1 + diff2 + diff3;
00272 a += 4;
00273 if ((worst_dist>0)&&(result>worst_dist)) {
00274 return result;
00275 }
00276 }
00277
00278 while (a < last) {
00279 result += nanoflann::abs( *a++ - data_source.kdtree_get_pt(b_idx,d++) );
00280 }
00281 return result;
00282 }
00283
00284 template <typename U, typename V>
00285 inline DistanceType accum_dist(const U a, const V b, int ) const
00286 {
00287 return nanoflann::abs(a-b);
00288 }
00289 };
00290
00296 template<class T, class DataSource, typename _DistanceType = T>
00297 struct L2_Adaptor
00298 {
00299 typedef T ElementType;
00300 typedef _DistanceType DistanceType;
00301
00302 const DataSource &data_source;
00303
00304 L2_Adaptor(const DataSource &_data_source) : data_source(_data_source) { }
00305
00306 inline DistanceType operator()(const T* a, const size_t b_idx, size_t size, DistanceType worst_dist = -1) const
00307 {
00308 DistanceType result = DistanceType();
00309 const T* last = a + size;
00310 const T* lastgroup = last - 3;
00311 size_t d = 0;
00312
00313
00314 while (a < lastgroup) {
00315 const DistanceType diff0 = a[0] - data_source.kdtree_get_pt(b_idx,d++);
00316 const DistanceType diff1 = a[1] - data_source.kdtree_get_pt(b_idx,d++);
00317 const DistanceType diff2 = a[2] - data_source.kdtree_get_pt(b_idx,d++);
00318 const DistanceType diff3 = a[3] - data_source.kdtree_get_pt(b_idx,d++);
00319 result += diff0 * diff0 + diff1 * diff1 + diff2 * diff2 + diff3 * diff3;
00320 a += 4;
00321 if ((worst_dist>0)&&(result>worst_dist)) {
00322 return result;
00323 }
00324 }
00325
00326 while (a < last) {
00327 const DistanceType diff0 = *a++ - data_source.kdtree_get_pt(b_idx,d++);
00328 result += diff0 * diff0;
00329 }
00330 return result;
00331 }
00332
00333 template <typename U, typename V>
00334 inline DistanceType accum_dist(const U a, const V b, int ) const
00335 {
00336 return (a-b)*(a-b);
00337 }
00338 };
00339
00345 template<class T, class DataSource, typename _DistanceType = T>
00346 struct L2_Simple_Adaptor
00347 {
00348 typedef T ElementType;
00349 typedef _DistanceType DistanceType;
00350
00351 const DataSource &data_source;
00352
00353 L2_Simple_Adaptor(const DataSource &_data_source) : data_source(_data_source) { }
00354
00355 inline DistanceType operator()(const T* a, const size_t b_idx, size_t size) const {
00356 return data_source.kdtree_distance(a,b_idx,size);
00357 }
00358
00359 template <typename U, typename V>
00360 inline DistanceType accum_dist(const U a, const V b, int ) const
00361 {
00362 return (a-b)*(a-b);
00363 }
00364 };
00365
00367 struct metric_L1 {
00368 template<class T, class DataSource>
00369 struct traits {
00370 typedef L1_Adaptor<T,DataSource> distance_t;
00371 };
00372 };
00374 struct metric_L2 {
00375 template<class T, class DataSource>
00376 struct traits {
00377 typedef L2_Adaptor<T,DataSource> distance_t;
00378 };
00379 };
00381 struct metric_L2_Simple {
00382 template<class T, class DataSource>
00383 struct traits {
00384 typedef L2_Simple_Adaptor<T,DataSource> distance_t;
00385 };
00386 };
00387
00397 struct KDTreeSingleIndexAdaptorParams
00398 {
00399 KDTreeSingleIndexAdaptorParams(size_t _leaf_max_size = 10, int dim_ = -1) :
00400 leaf_max_size(_leaf_max_size), dim(dim_)
00401 {}
00402
00403 size_t leaf_max_size;
00404 int dim;
00405 };
00406
00408 struct SearchParams
00409 {
00411 SearchParams(int checks_IGNORED_ = 32, float eps_ = 0, bool sorted_ = true ) :
00412 checks(checks_IGNORED_), eps(eps_), sorted(sorted_) {}
00413
00414 int checks;
00415 float eps;
00416 bool sorted;
00417 };
00431 template <typename T>
00432 inline T* allocate(size_t count = 1)
00433 {
00434 T* mem = (T*) ::malloc(sizeof(T)*count);
00435 return mem;
00436 }
00437
00438
00454 const size_t WORDSIZE=16;
00455 const size_t BLOCKSIZE=8192;
00456
00457 class PooledAllocator
00458 {
00459
00460
00461
00462
00463
00464
00465 size_t remaining;
00466 void* base;
00467 void* loc;
00468 size_t blocksize;
00469
00470 void internal_init()
00471 {
00472 remaining = 0;
00473 base = NULL;
00474 usedMemory = 0;
00475 wastedMemory = 0;
00476 }
00477
00478 public:
00479 size_t usedMemory;
00480 size_t wastedMemory;
00481
00485 PooledAllocator(const size_t blocksize_ = BLOCKSIZE) : blocksize(blocksize_) {
00486 internal_init();
00487 }
00488
00492 ~PooledAllocator() {
00493 free_all();
00494 }
00495
00497 void free_all()
00498 {
00499 while (base != NULL) {
00500 void *prev = *((void**) base);
00501 ::free(base);
00502 base = prev;
00503 }
00504 internal_init();
00505 }
00506
00511 void* malloc(const size_t req_size)
00512 {
00513
00514
00515
00516
00517 const size_t size = (req_size + (WORDSIZE - 1)) & ~(WORDSIZE - 1);
00518
00519
00520
00521
00522 if (size > remaining) {
00523
00524 wastedMemory += remaining;
00525
00526
00527 const size_t blocksize = (size + sizeof(void*) + (WORDSIZE-1) > BLOCKSIZE) ?
00528 size + sizeof(void*) + (WORDSIZE-1) : BLOCKSIZE;
00529
00530
00531 void* m = ::malloc(blocksize);
00532 if (!m) {
00533 fprintf(stderr,"Failed to allocate memory.\n");
00534 return NULL;
00535 }
00536
00537
00538 ((void**) m)[0] = base;
00539 base = m;
00540
00541 size_t shift = 0;
00542
00543
00544 remaining = blocksize - sizeof(void*) - shift;
00545 loc = ((char*)m + sizeof(void*) + shift);
00546 }
00547 void* rloc = loc;
00548 loc = (char*)loc + size;
00549 remaining -= size;
00550
00551 usedMemory += size;
00552
00553 return rloc;
00554 }
00555
00563 template <typename T>
00564 T* allocate(const size_t count = 1)
00565 {
00566 T* mem = (T*) this->malloc(sizeof(T)*count);
00567 return mem;
00568 }
00569
00570 };
00576
00602 template <typename T, std::size_t N>
00603 class CArray {
00604 public:
00605 T elems[N];
00606
00607 public:
00608
00609 typedef T value_type;
00610 typedef T* iterator;
00611 typedef const T* const_iterator;
00612 typedef T& reference;
00613 typedef const T& const_reference;
00614 typedef std::size_t size_type;
00615 typedef std::ptrdiff_t difference_type;
00616
00617
00618 inline iterator begin() { return elems; }
00619 inline const_iterator begin() const { return elems; }
00620 inline iterator end() { return elems+N; }
00621 inline const_iterator end() const { return elems+N; }
00622
00623
00624 #if !defined(BOOST_NO_TEMPLATE_PARTIAL_SPECIALIZATION) && !defined(BOOST_MSVC_STD_ITERATOR) && !defined(BOOST_NO_STD_ITERATOR_TRAITS)
00625 typedef std::reverse_iterator<iterator> reverse_iterator;
00626 typedef std::reverse_iterator<const_iterator> const_reverse_iterator;
00627 #elif defined(_MSC_VER) && (_MSC_VER == 1300) && defined(BOOST_DINKUMWARE_STDLIB) && (BOOST_DINKUMWARE_STDLIB == 310)
00628
00629 typedef std::reverse_iterator<std::_Ptrit<value_type, difference_type, iterator,
00630 reference, iterator, reference> > reverse_iterator;
00631 typedef std::reverse_iterator<std::_Ptrit<value_type, difference_type, const_iterator,
00632 const_reference, iterator, reference> > const_reverse_iterator;
00633 #else
00634
00635 typedef std::reverse_iterator<iterator,T> reverse_iterator;
00636 typedef std::reverse_iterator<const_iterator,T> const_reverse_iterator;
00637 #endif
00638
00639 reverse_iterator rbegin() { return reverse_iterator(end()); }
00640 const_reverse_iterator rbegin() const { return const_reverse_iterator(end()); }
00641 reverse_iterator rend() { return reverse_iterator(begin()); }
00642 const_reverse_iterator rend() const { return const_reverse_iterator(begin()); }
00643
00644 inline reference operator[](size_type i) { return elems[i]; }
00645 inline const_reference operator[](size_type i) const { return elems[i]; }
00646
00647 reference at(size_type i) { rangecheck(i); return elems[i]; }
00648 const_reference at(size_type i) const { rangecheck(i); return elems[i]; }
00649
00650 reference front() { return elems[0]; }
00651 const_reference front() const { return elems[0]; }
00652 reference back() { return elems[N-1]; }
00653 const_reference back() const { return elems[N-1]; }
00654
00655 static inline size_type size() { return N; }
00656 static bool empty() { return false; }
00657 static size_type max_size() { return N; }
00658 enum { static_size = N };
00660 inline void resize(const size_t nElements) { if (nElements!=N) throw std::logic_error("Try to change the size of a CArray."); }
00661
00662 void swap (CArray<T,N>& y) { std::swap_ranges(begin(),end(),y.begin()); }
00663
00664 const T* data() const { return elems; }
00665
00666 T* data() { return elems; }
00667
00668 template <typename T2> CArray<T,N>& operator= (const CArray<T2,N>& rhs) {
00669 std::copy(rhs.begin(),rhs.end(), begin());
00670 return *this;
00671 }
00672
00673 inline void assign (const T& value) { for (size_t i=0;i<N;i++) elems[i]=value; }
00674
00675 void assign (const size_t n, const T& value) { assert(N==n); for (size_t i=0;i<N;i++) elems[i]=value; }
00676 private:
00677
00678 static void rangecheck (size_type i) { if (i >= size()) { throw std::out_of_range("CArray<>: index out of range"); } }
00679 };
00680
00684 template <int DIM, typename T>
00685 struct array_or_vector_selector
00686 {
00687 typedef CArray<T,DIM> container_t;
00688 };
00690 template <typename T>
00691 struct array_or_vector_selector<-1,T> {
00692 typedef std::vector<T> container_t;
00693 };
00732 template <typename Distance, class DatasetAdaptor,int DIM = -1, typename IndexType = size_t>
00733 class KDTreeSingleIndexAdaptor
00734 {
00735 private:
00737 KDTreeSingleIndexAdaptor(const KDTreeSingleIndexAdaptor<Distance,DatasetAdaptor,DIM,IndexType>&);
00738 public:
00739 typedef typename Distance::ElementType ElementType;
00740 typedef typename Distance::DistanceType DistanceType;
00741 protected:
00742
00746 std::vector<IndexType> vind;
00747
00748 size_t m_leaf_max_size;
00749
00750
00754 const DatasetAdaptor &dataset;
00755
00756 const KDTreeSingleIndexAdaptorParams index_params;
00757
00758 size_t m_size;
00759 int dim;
00760
00761
00762
00763 struct Node
00764 {
00765 union {
00766 struct
00767 {
00771 IndexType left, right;
00772 } lr;
00773 struct
00774 {
00778 int divfeat;
00782 DistanceType divlow, divhigh;
00783 } sub;
00784 };
00788 Node* child1, * child2;
00789 };
00790 typedef Node* NodePtr;
00791
00792
00793 struct Interval
00794 {
00795 ElementType low, high;
00796 };
00797
00799 typedef typename array_or_vector_selector<DIM,Interval>::container_t BoundingBox;
00800
00802 typedef typename array_or_vector_selector<DIM,DistanceType>::container_t distance_vector_t;
00803
00808 template <typename T, typename DistanceType>
00809 struct BranchStruct
00810 {
00811 T node;
00812 DistanceType mindist;
00813
00814 BranchStruct() {}
00815 BranchStruct(const T& aNode, DistanceType dist) : node(aNode), mindist(dist) {}
00816
00817 inline bool operator<(const BranchStruct<T, DistanceType>& rhs) const
00818 {
00819 return mindist<rhs.mindist;
00820 }
00821 };
00822
00826 NodePtr root_node;
00827 typedef BranchStruct<NodePtr, DistanceType> BranchSt;
00828 typedef BranchSt* Branch;
00829
00830 BoundingBox root_bbox;
00831
00839 PooledAllocator pool;
00840
00841 public:
00842
00843 Distance distance;
00844
00852 KDTreeSingleIndexAdaptor(const int dimensionality, const DatasetAdaptor& inputData, const KDTreeSingleIndexAdaptorParams& params = KDTreeSingleIndexAdaptorParams() ) :
00853 dataset(inputData), index_params(params), root_node(NULL), distance(inputData)
00854 {
00855 m_size = dataset.kdtree_get_point_count();
00856 dim = dimensionality;
00857 if (DIM>0) dim=DIM;
00858 else {
00859 if (params.dim>0) dim = params.dim;
00860 }
00861 m_leaf_max_size = params.leaf_max_size;
00862
00863
00864 init_vind();
00865 }
00866
00870 ~KDTreeSingleIndexAdaptor()
00871 {
00872 }
00873
00875 void freeIndex()
00876 {
00877 pool.free_all();
00878 root_node=NULL;
00879 }
00880
00884 void buildIndex()
00885 {
00886 init_vind();
00887 freeIndex();
00888 if(m_size == 0) return;
00889 computeBoundingBox(root_bbox);
00890 root_node = divideTree(0, m_size, root_bbox );
00891 }
00892
00896 size_t size() const
00897 {
00898 return m_size;
00899 }
00900
00904 size_t veclen() const
00905 {
00906 return static_cast<size_t>(DIM>0 ? DIM : dim);
00907 }
00908
00913 size_t usedMemory() const
00914 {
00915 return pool.usedMemory+pool.wastedMemory+dataset.kdtree_get_point_count()*sizeof(IndexType);
00916 }
00917
00932 template <typename RESULTSET>
00933 void findNeighbors(RESULTSET& result, const ElementType* vec, const SearchParams& searchParams) const
00934 {
00935 assert(vec);
00936 if (!root_node) throw std::runtime_error("[nanoflann] findNeighbors() called before building the index or no data points.");
00937 float epsError = 1+searchParams.eps;
00938
00939 distance_vector_t dists;
00940 dists.assign((DIM>0 ? DIM : dim) ,0);
00941 DistanceType distsq = computeInitialDistances(vec, dists);
00942 searchLevel(result, vec, root_node, distsq, dists, epsError);
00943 }
00944
00951 inline void knnSearch(const ElementType *query_point, const size_t num_closest, IndexType *out_indices, DistanceType *out_distances_sq, const int nChecks_IGNORED = 10) const
00952 {
00953 nanoflann::KNNResultSet<DistanceType,IndexType> resultSet(num_closest);
00954 resultSet.init(out_indices, out_distances_sq);
00955 this->findNeighbors(resultSet, query_point, nanoflann::SearchParams());
00956 }
00957
00970 size_t radiusSearch(const ElementType *query_point,const DistanceType radius, std::vector<std::pair<IndexType,DistanceType> >& IndicesDists, const SearchParams& searchParams) const
00971 {
00972 RadiusResultSet<DistanceType,IndexType> resultSet(radius,IndicesDists);
00973 this->findNeighbors(resultSet, query_point, searchParams);
00974
00975 if (searchParams.sorted)
00976 std::sort(IndicesDists.begin(),IndicesDists.end(), IndexDist_Sorter() );
00977
00978 return resultSet.size();
00979 }
00980
00983 private:
00985 void init_vind()
00986 {
00987
00988 m_size = dataset.kdtree_get_point_count();
00989 if (vind.size()!=m_size) vind.resize(m_size);
00990 for (size_t i = 0; i < m_size; i++) vind[i] = i;
00991 }
00992
00994 inline ElementType dataset_get(size_t idx, int component) const {
00995 return dataset.kdtree_get_pt(idx,component);
00996 }
00997
00998
00999 void save_tree(FILE* stream, NodePtr tree)
01000 {
01001 save_value(stream, *tree);
01002 if (tree->child1!=NULL) {
01003 save_tree(stream, tree->child1);
01004 }
01005 if (tree->child2!=NULL) {
01006 save_tree(stream, tree->child2);
01007 }
01008 }
01009
01010
01011 void load_tree(FILE* stream, NodePtr& tree)
01012 {
01013 tree = pool.allocate<Node>();
01014 load_value(stream, *tree);
01015 if (tree->child1!=NULL) {
01016 load_tree(stream, tree->child1);
01017 }
01018 if (tree->child2!=NULL) {
01019 load_tree(stream, tree->child2);
01020 }
01021 }
01022
01023
01024 void computeBoundingBox(BoundingBox& bbox)
01025 {
01026 bbox.resize((DIM>0 ? DIM : dim));
01027 if (dataset.kdtree_get_bbox(bbox))
01028 {
01029
01030 }
01031 else
01032 {
01033 const size_t N = dataset.kdtree_get_point_count();
01034 if (!N) throw std::runtime_error("[nanoflann] computeBoundingBox() called but no data points found.");
01035 for (int i=0; i<(DIM>0 ? DIM : dim); ++i) {
01036 bbox[i].low =
01037 bbox[i].high = dataset_get(0,i);
01038 }
01039 for (size_t k=1; k<N; ++k) {
01040 for (int i=0; i<(DIM>0 ? DIM : dim); ++i) {
01041 if (dataset_get(k,i)<bbox[i].low) bbox[i].low = dataset_get(k,i);
01042 if (dataset_get(k,i)>bbox[i].high) bbox[i].high = dataset_get(k,i);
01043 }
01044 }
01045 }
01046 }
01047
01048
01058 NodePtr divideTree(const IndexType left, const IndexType right, BoundingBox& bbox)
01059 {
01060 NodePtr node = pool.allocate<Node>();
01061
01062
01063 if ( (right-left) <= m_leaf_max_size) {
01064 node->child1 = node->child2 = NULL;
01065 node->lr.left = left;
01066 node->lr.right = right;
01067
01068
01069 for (int i=0; i<(DIM>0 ? DIM : dim); ++i) {
01070 bbox[i].low = dataset_get(vind[left],i);
01071 bbox[i].high = dataset_get(vind[left],i);
01072 }
01073 for (IndexType k=left+1; k<right; ++k) {
01074 for (int i=0; i<(DIM>0 ? DIM : dim); ++i) {
01075 if (bbox[i].low>dataset_get(vind[k],i)) bbox[i].low=dataset_get(vind[k],i);
01076 if (bbox[i].high<dataset_get(vind[k],i)) bbox[i].high=dataset_get(vind[k],i);
01077 }
01078 }
01079 }
01080 else {
01081 IndexType idx;
01082 int cutfeat;
01083 DistanceType cutval;
01084 middleSplit_(&vind[0]+left, right-left, idx, cutfeat, cutval, bbox);
01085
01086 node->sub.divfeat = cutfeat;
01087
01088 BoundingBox left_bbox(bbox);
01089 left_bbox[cutfeat].high = cutval;
01090 node->child1 = divideTree(left, left+idx, left_bbox);
01091
01092 BoundingBox right_bbox(bbox);
01093 right_bbox[cutfeat].low = cutval;
01094 node->child2 = divideTree(left+idx, right, right_bbox);
01095
01096 node->sub.divlow = left_bbox[cutfeat].high;
01097 node->sub.divhigh = right_bbox[cutfeat].low;
01098
01099 for (int i=0; i<(DIM>0 ? DIM : dim); ++i) {
01100 bbox[i].low = std::min(left_bbox[i].low, right_bbox[i].low);
01101 bbox[i].high = std::max(left_bbox[i].high, right_bbox[i].high);
01102 }
01103 }
01104
01105 return node;
01106 }
01107
01108 void computeMinMax(IndexType* ind, IndexType count, int element, ElementType& min_elem, ElementType& max_elem)
01109 {
01110 min_elem = dataset_get(ind[0],element);
01111 max_elem = dataset_get(ind[0],element);
01112 for (IndexType i=1; i<count; ++i) {
01113 ElementType val = dataset_get(ind[i],element);
01114 if (val<min_elem) min_elem = val;
01115 if (val>max_elem) max_elem = val;
01116 }
01117 }
01118
01119 void middleSplit(IndexType* ind, IndexType count, IndexType& index, int& cutfeat, DistanceType& cutval, const BoundingBox& bbox)
01120 {
01121
01122 ElementType max_span = bbox[0].high-bbox[0].low;
01123 cutfeat = 0;
01124 cutval = (bbox[0].high+bbox[0].low)/2;
01125 for (int i=1; i<(DIM>0 ? DIM : dim); ++i) {
01126 ElementType span = bbox[i].low-bbox[i].low;
01127 if (span>max_span) {
01128 max_span = span;
01129 cutfeat = i;
01130 cutval = (bbox[i].high+bbox[i].low)/2;
01131 }
01132 }
01133
01134
01135 ElementType min_elem, max_elem;
01136 computeMinMax(ind, count, cutfeat, min_elem, max_elem);
01137 cutval = (min_elem+max_elem)/2;
01138 max_span = max_elem - min_elem;
01139
01140
01141 size_t k = cutfeat;
01142 for (size_t i=0; i<(DIM>0 ? DIM : dim); ++i) {
01143 if (i==k) continue;
01144 ElementType span = bbox[i].high-bbox[i].low;
01145 if (span>max_span) {
01146 computeMinMax(ind, count, i, min_elem, max_elem);
01147 span = max_elem - min_elem;
01148 if (span>max_span) {
01149 max_span = span;
01150 cutfeat = i;
01151 cutval = (min_elem+max_elem)/2;
01152 }
01153 }
01154 }
01155 IndexType lim1, lim2;
01156 planeSplit(ind, count, cutfeat, cutval, lim1, lim2);
01157
01158 if (lim1>count/2) index = lim1;
01159 else if (lim2<count/2) index = lim2;
01160 else index = count/2;
01161 }
01162
01163
01164 void middleSplit_(IndexType* ind, IndexType count, IndexType& index, int& cutfeat, DistanceType& cutval, const BoundingBox& bbox)
01165 {
01166 const DistanceType EPS=static_cast<DistanceType>(0.00001);
01167 ElementType max_span = bbox[0].high-bbox[0].low;
01168 for (int i=1; i<(DIM>0 ? DIM : dim); ++i) {
01169 ElementType span = bbox[i].high-bbox[i].low;
01170 if (span>max_span) {
01171 max_span = span;
01172 }
01173 }
01174 ElementType max_spread = -1;
01175 cutfeat = 0;
01176 for (int i=0; i<(DIM>0 ? DIM : dim); ++i) {
01177 ElementType span = bbox[i].high-bbox[i].low;
01178 if (span>(1-EPS)*max_span) {
01179 ElementType min_elem, max_elem;
01180 computeMinMax(ind, count, cutfeat, min_elem, max_elem);
01181 ElementType spread = max_elem-min_elem;;
01182 if (spread>max_spread) {
01183 cutfeat = i;
01184 max_spread = spread;
01185 }
01186 }
01187 }
01188
01189 DistanceType split_val = (bbox[cutfeat].low+bbox[cutfeat].high)/2;
01190 ElementType min_elem, max_elem;
01191 computeMinMax(ind, count, cutfeat, min_elem, max_elem);
01192
01193 if (split_val<min_elem) cutval = min_elem;
01194 else if (split_val>max_elem) cutval = max_elem;
01195 else cutval = split_val;
01196
01197 IndexType lim1, lim2;
01198 planeSplit(ind, count, cutfeat, cutval, lim1, lim2);
01199
01200 if (lim1>count/2) index = lim1;
01201 else if (lim2<count/2) index = lim2;
01202 else index = count/2;
01203 }
01204
01205
01215 void planeSplit(IndexType* ind, const IndexType count, int cutfeat, DistanceType cutval, IndexType& lim1, IndexType& lim2)
01216 {
01217
01218 IndexType left = 0;
01219 IndexType right = count-1;
01220 for (;; ) {
01221 while (left<=right && dataset_get(ind[left],cutfeat)<cutval) ++left;
01222 while (right && left<=right && dataset_get(ind[right],cutfeat)>=cutval) --right;
01223 if (left>right || !right) break;
01224 std::swap(ind[left], ind[right]);
01225 ++left;
01226 --right;
01227 }
01228
01229
01230
01231 lim1 = left;
01232 right = count-1;
01233 for (;; ) {
01234 while (left<=right && dataset_get(ind[left],cutfeat)<=cutval) ++left;
01235 while (right && left<=right && dataset_get(ind[right],cutfeat)>cutval) --right;
01236 if (left>right || !right) break;
01237 std::swap(ind[left], ind[right]);
01238 ++left;
01239 --right;
01240 }
01241 lim2 = left;
01242 }
01243
01244 DistanceType computeInitialDistances(const ElementType* vec, distance_vector_t& dists) const
01245 {
01246 assert(vec);
01247 DistanceType distsq = 0.0;
01248
01249 for (int i = 0; i < (DIM>0 ? DIM : dim); ++i) {
01250 if (vec[i] < root_bbox[i].low) {
01251 dists[i] = distance.accum_dist(vec[i], root_bbox[i].low, i);
01252 distsq += dists[i];
01253 }
01254 if (vec[i] > root_bbox[i].high) {
01255 dists[i] = distance.accum_dist(vec[i], root_bbox[i].high, i);
01256 distsq += dists[i];
01257 }
01258 }
01259
01260 return distsq;
01261 }
01262
01267 template <class RESULTSET>
01268 void searchLevel(RESULTSET& result_set, const ElementType* vec, const NodePtr node, DistanceType mindistsq,
01269 distance_vector_t& dists, const float epsError) const
01270 {
01271
01272 if ((node->child1 == NULL)&&(node->child2 == NULL)) {
01273
01274 DistanceType worst_dist = result_set.worstDist();
01275 for (IndexType i=node->lr.left; i<node->lr.right; ++i) {
01276 const IndexType index = vind[i];
01277 DistanceType dist = distance(vec, index, (DIM>0 ? DIM : dim));
01278 if (dist<worst_dist) {
01279 result_set.addPoint(dist,vind[i]);
01280 }
01281 }
01282 return;
01283 }
01284
01285
01286 int idx = node->sub.divfeat;
01287 ElementType val = vec[idx];
01288 DistanceType diff1 = val - node->sub.divlow;
01289 DistanceType diff2 = val - node->sub.divhigh;
01290
01291 NodePtr bestChild;
01292 NodePtr otherChild;
01293 DistanceType cut_dist;
01294 if ((diff1+diff2)<0) {
01295 bestChild = node->child1;
01296 otherChild = node->child2;
01297 cut_dist = distance.accum_dist(val, node->sub.divhigh, idx);
01298 }
01299 else {
01300 bestChild = node->child2;
01301 otherChild = node->child1;
01302 cut_dist = distance.accum_dist( val, node->sub.divlow, idx);
01303 }
01304
01305
01306 searchLevel(result_set, vec, bestChild, mindistsq, dists, epsError);
01307
01308 DistanceType dst = dists[idx];
01309 mindistsq = mindistsq + cut_dist - dst;
01310 dists[idx] = cut_dist;
01311 if (mindistsq*epsError<=result_set.worstDist()) {
01312 searchLevel(result_set, vec, otherChild, mindistsq, dists, epsError);
01313 }
01314 dists[idx] = dst;
01315 }
01316
01317 public:
01322 void saveIndex(FILE* stream)
01323 {
01324 save_value(stream, m_size);
01325 save_value(stream, dim);
01326 save_value(stream, root_bbox);
01327 save_value(stream, m_leaf_max_size);
01328 save_value(stream, vind);
01329 save_tree(stream, root_node);
01330 }
01331
01336 void loadIndex(FILE* stream)
01337 {
01338 load_value(stream, m_size);
01339 load_value(stream, dim);
01340 load_value(stream, root_bbox);
01341 load_value(stream, m_leaf_max_size);
01342 load_value(stream, vind);
01343 load_tree(stream, root_node);
01344 }
01345
01346 };
01347
01348
01368 template <class MatrixType, int DIM = -1, class Distance = nanoflann::metric_L2, typename IndexType = size_t>
01369 struct KDTreeEigenMatrixAdaptor
01370 {
01371 typedef KDTreeEigenMatrixAdaptor<MatrixType,DIM,Distance,IndexType> self_t;
01372 typedef typename MatrixType::Scalar num_t;
01373 typedef typename Distance::template traits<num_t,self_t>::distance_t metric_t;
01374 typedef KDTreeSingleIndexAdaptor< metric_t,self_t,DIM,IndexType> index_t;
01375
01376 index_t* index;
01377
01379 KDTreeEigenMatrixAdaptor(const int dimensionality, const MatrixType &mat, const int leaf_max_size = 10) : m_data_matrix(mat)
01380 {
01381 const size_t dims = mat.cols();
01382 if (DIM>0 && static_cast<int>(dims)!=DIM)
01383 throw std::runtime_error("Data set dimensionality does not match the 'DIM' template argument");
01384 index = new index_t( dims, *this , nanoflann::KDTreeSingleIndexAdaptorParams(leaf_max_size, dims ) );
01385 index->buildIndex();
01386 }
01387 private:
01389 KDTreeEigenMatrixAdaptor(const self_t&);
01390 public:
01391
01392 ~KDTreeEigenMatrixAdaptor() {
01393 delete index;
01394 }
01395
01396 const MatrixType &m_data_matrix;
01397
01403 inline void query(const num_t *query_point, const size_t num_closest, IndexType *out_indices, num_t *out_distances_sq, const int nChecks_IGNORED = 10) const
01404 {
01405 nanoflann::KNNResultSet<typename MatrixType::Scalar,IndexType> resultSet(num_closest);
01406 resultSet.init(out_indices, out_distances_sq);
01407 index->findNeighbors(resultSet, query_point, nanoflann::SearchParams());
01408 }
01409
01413 const self_t & derived() const {
01414 return *this;
01415 }
01416 self_t & derived() {
01417 return *this;
01418 }
01419
01420
01421 inline size_t kdtree_get_point_count() const {
01422 return m_data_matrix.rows();
01423 }
01424
01425
01426 inline num_t kdtree_distance(const num_t *p1, const size_t idx_p2,size_t size) const
01427 {
01428 num_t s=0;
01429 for (size_t i=0; i<size; i++) {
01430 const num_t d= p1[i]-m_data_matrix.coeff(idx_p2,i);
01431 s+=d*d;
01432 }
01433 return s;
01434 }
01435
01436
01437 inline num_t kdtree_get_pt(const size_t idx, int dim) const {
01438 return m_data_matrix.coeff(idx,dim);
01439 }
01440
01441
01442
01443
01444 template <class BBOX>
01445 bool kdtree_get_bbox(BBOX &bb) const {
01446 return false;
01447 }
01448
01451 };
01455 }
01456
01457
01458 #endif