heap.h
Go to the documentation of this file.
00001 /***********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright 2008-2009  Marius Muja (mariusm@cs.ubc.ca). All rights reserved.
00005  * Copyright 2008-2009  David G. Lowe (lowe@cs.ubc.ca). All rights reserved.
00006  *
00007  * THE BSD LICENSE
00008  *
00009  * Redistribution and use in source and binary forms, with or without
00010  * modification, are permitted provided that the following conditions
00011  * are met:
00012  *
00013  * 1. Redistributions of source code must retain the above copyright
00014  *    notice, this list of conditions and the following disclaimer.
00015  * 2. Redistributions in binary form must reproduce the above copyright
00016  *    notice, this list of conditions and the following disclaimer in the
00017  *    documentation and/or other materials provided with the distribution.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
00020  * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
00021  * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
00022  * IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT,
00023  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
00024  * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
00025  * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
00026  * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00027  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
00028  * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00029  *************************************************************************/
00030 
00031 #ifndef RTABMAP_FLANN_HEAP_H_
00032 #define RTABMAP_FLANN_HEAP_H_
00033 
00034 #include <algorithm>
00035 #include <vector>
00036 
00037 namespace rtflann
00038 {
00039 
00047 template <typename T>
00048 class Heap
00049 {
00050 
00055     std::vector<T> heap;
00056     int length;
00057 
00061     int count;
00062 
00063 
00064 
00065 public:
00073     Heap(int size)
00074     {
00075         length = size;
00076         heap.reserve(length);
00077         count = 0;
00078     }
00079 
00084     int size()
00085     {
00086         return count;
00087     }
00088 
00094     bool empty()
00095     {
00096         return size()==0;
00097     }
00098 
00102     void clear()
00103     {
00104         heap.clear();
00105         count = 0;
00106     }
00107 
00108     struct CompareT : public std::binary_function<T,T,bool>
00109     {
00110         bool operator()(const T& t_1, const T& t_2) const
00111         {
00112             return t_2 < t_1;
00113         }
00114     };
00115 
00125     void insert(const T& value)
00126     {
00127         /* If heap is full, then return without adding this element. */
00128         if (count == length) {
00129             return;
00130         }
00131 
00132         heap.push_back(value);
00133         static CompareT compareT;
00134         std::push_heap(heap.begin(), heap.end(), compareT);
00135         ++count;
00136     }
00137 
00138 
00139 
00147     bool popMin(T& value)
00148     {
00149         if (count == 0) {
00150             return false;
00151         }
00152 
00153         value = heap[0];
00154         static CompareT compareT;
00155         std::pop_heap(heap.begin(), heap.end(), compareT);
00156         heap.pop_back();
00157         --count;
00158 
00159         return true;  /* Return old last node. */
00160     }
00161 };
00162 
00163 
00164 template <typename T>
00165 class IntervalHeap
00166 {
00167         struct Interval
00168         {
00169                 T left;
00170                 T right;
00171         };
00172 
00177     std::vector<Interval> heap;
00178     size_t capacity_;
00179     size_t size_;
00180 
00181 public:
00189     IntervalHeap(int capacity) : capacity_(capacity), size_(0)
00190     {
00191         heap.resize(capacity/2 + capacity%2 + 1); // 1-based indexing
00192     }
00193 
00197     size_t size()
00198     {
00199         return size_;
00200     }
00201 
00206     bool empty()
00207     {
00208         return size_==0;
00209     }
00210 
00214     void clear()
00215     {
00216         size_ = 0;
00217     }
00218 
00219     void insert(const T& value)
00220     {
00221         /* If heap is full, then return without adding this element. */
00222         if (size_ == capacity_) {
00223             return;
00224         }
00225 
00226         // insert into the root
00227         if (size_<2) {
00228                 if (size_==0) {
00229                         heap[1].left = value;
00230                         heap[1].right = value;
00231                 }
00232                 else {
00233                         if (value<heap[1].left) {
00234                                 heap[1].left = value;
00235                         }
00236                         else {
00237                                 heap[1].right = value;
00238                         }
00239                 }
00240                 ++size_;
00241                 return;
00242         }
00243 
00244         size_t last_pos = size_/2 + size_%2;
00245         bool min_heap;
00246 
00247         if (size_%2) { // odd number of elements
00248                 min_heap = (value<heap[last_pos].left)? true : false;
00249         }
00250         else {
00251                 ++last_pos;
00252                 min_heap = (value<heap[last_pos/2].left)? true : false;
00253         }
00254 
00255         if (min_heap) {
00256                 size_t pos = last_pos;
00257                 size_t par = pos/2;
00258                 while (pos>1 && value < heap[par].left) {
00259                         heap[pos].left = heap[par].left;
00260                         pos = par;
00261                         par = pos/2;
00262                 }
00263                 heap[pos].left = value;
00264                 ++size_;
00265 
00266                 if (size_%2) { // duplicate element in last position if size is odd
00267                         heap[last_pos].right = heap[last_pos].left;
00268                 }
00269         }
00270         else {
00271                 size_t pos = last_pos;
00272                 size_t par = pos/2;
00273                 while (pos>1 && heap[par].right < value) {
00274                         heap[pos].right = heap[par].right;
00275                         pos = par;
00276                         par = pos/2;
00277                 }
00278                 heap[pos].right = value;
00279                 ++size_;
00280 
00281                 if (size_%2) { // duplicate element in last position if size is odd
00282                         heap[last_pos].left = heap[last_pos].right;
00283                 }
00284         }
00285     }
00286 
00287 
00293     bool popMin(T& value)
00294     {
00295         if (size_ == 0) {
00296             return false;
00297         }
00298 
00299         value = heap[1].left;
00300         size_t last_pos = size_/2 + size_%2;
00301         T elem = heap[last_pos].left;
00302 
00303         if (size_ % 2) { // odd number of elements
00304                 --last_pos;
00305         }
00306         else {
00307                 heap[last_pos].left = heap[last_pos].right;
00308         }
00309         --size_;
00310         if (size_<2) return true;
00311 
00312         size_t crt=1; // root node
00313         size_t child = crt*2;
00314 
00315         while (child <= last_pos) {
00316                 if (child < last_pos && heap[child+1].left < heap[child].left) ++child; // pick the child with min
00317 
00318                 if (!(heap[child].left<elem)) break;
00319 
00320                 heap[crt].left = heap[child].left;
00321                 if (heap[child].right<elem) {
00322                         std::swap(elem, heap[child].right);
00323                 }
00324 
00325                 crt = child;
00326                 child *= 2;
00327         }
00328         heap[crt].left = elem;
00329         return true;
00330     }
00331 
00332 
00338     bool popMax(T& value)
00339     {
00340         if (size_ == 0) {
00341             return false;
00342         }
00343 
00344         value = heap[1].right;
00345         size_t last_pos = size_/2 + size_%2;
00346         T elem = heap[last_pos].right;
00347 
00348         if (size_%2) { // odd number of elements
00349                 --last_pos;
00350         }
00351         else {
00352                 heap[last_pos].right = heap[last_pos].left;
00353         }
00354         --size_;
00355         if (size_<2) return true;
00356 
00357         size_t crt=1; // root node
00358         size_t child = crt*2;
00359 
00360         while (child <= last_pos) {
00361                 if (child < last_pos && heap[child].right < heap[child+1].right) ++child; // pick the child with max
00362 
00363                 if (!(elem < heap[child].right)) break;
00364 
00365                 heap[crt].right = heap[child].right;
00366                 if (elem<heap[child].left) {
00367                         std::swap(elem, heap[child].left);
00368                 }
00369 
00370                 crt = child;
00371                 child *= 2;
00372         }
00373         heap[crt].right = elem;
00374         return true;
00375     }
00376 
00377 
00378     bool getMin(T& value)
00379     {
00380         if (size_==0) {
00381                 return false;
00382         }
00383         value = heap[1].left;
00384         return true;
00385     }
00386 
00387 
00388     bool getMax(T& value)
00389     {
00390         if (size_==0) {
00391                 return false;
00392         }
00393         value = heap[1].right;
00394         return true;
00395     }
00396 };
00397 
00398 
00399 template <typename T>
00400 class BoundedHeap
00401 {
00402         IntervalHeap<T> interval_heap_;
00403         size_t capacity_;
00404 public:
00405         BoundedHeap(size_t capacity) : interval_heap_(capacity), capacity_(capacity)
00406         {
00407 
00408         }
00409 
00413     int size()
00414     {
00415         return interval_heap_.size();
00416     }
00417 
00422     bool empty()
00423     {
00424         return interval_heap_.empty();
00425     }
00426 
00430     void clear()
00431     {
00432         interval_heap_.clear();
00433     }
00434 
00435     void insert(const T& value)
00436     {
00437         if (interval_heap_.size()==capacity_) {
00438                 T max;
00439                 interval_heap_.getMax(max);
00440                 if (max<value) return;
00441                         interval_heap_.popMax(max);
00442         }
00443         interval_heap_.insert(value);
00444     }
00445 
00446     bool popMin(T& value)
00447     {
00448         return interval_heap_.popMin(value);
00449     }
00450 };
00451 
00452 
00453 
00454 }
00455 
00456 #endif //FLANN_HEAP_H_


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:16