result_set.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_RESULTSET_H
00032 #define RTABMAP_FLANN_RESULTSET_H
00033 
00034 #include <algorithm>
00035 #include <cstring>
00036 #include <iostream>
00037 #include <limits>
00038 #include <set>
00039 #include <vector>
00040 
00041 namespace rtflann
00042 {
00043 
00044 /* This record represents a branch point when finding neighbors in
00045     the tree.  It contains a record of the minimum distance to the query
00046     point, as well as the node at which the search resumes.
00047  */
00048 
00049 template <typename T, typename DistanceType>
00050 struct BranchStruct
00051 {
00052     T node;           /* Tree node at which search resumes */
00053     DistanceType mindist;     /* Minimum distance to query for all nodes below. */
00054 
00055     BranchStruct() {}
00056     BranchStruct(const T& aNode, DistanceType dist) : node(aNode), mindist(dist) {}
00057 
00058     bool operator<(const BranchStruct<T, DistanceType>& rhs) const
00059     {
00060         return mindist<rhs.mindist;
00061     }
00062 };
00063 
00064 
00065 template <typename DistanceType>
00066 struct DistanceIndex
00067 {
00068     DistanceIndex(DistanceType dist, size_t index) :
00069         dist_(dist), index_(index)
00070     {
00071     }
00072     bool operator<(const DistanceIndex& dist_index) const
00073     {
00074         return (dist_ < dist_index.dist_) || ((dist_ == dist_index.dist_) && index_ < dist_index.index_);
00075     }
00076     DistanceType dist_;
00077     size_t index_;
00078 };
00079 
00080 
00081 template <typename DistanceType>
00082 class ResultSet
00083 {
00084 public:
00085     virtual ~ResultSet() {}
00086 
00087     virtual bool full() const = 0;
00088 
00089     virtual void addPoint(DistanceType dist, size_t index) = 0;
00090 
00091     virtual DistanceType worstDist() const = 0;
00092 
00093 };
00094 
00100 template <typename DistanceType>
00101 class KNNSimpleResultSet : public ResultSet<DistanceType>
00102 {
00103 public:
00104         typedef DistanceIndex<DistanceType> DistIndex;
00105 
00106         KNNSimpleResultSet(size_t capacity_) :
00107         capacity_(capacity_)
00108     {
00109                 // reserving capacity to prevent memory re-allocations
00110                 dist_index_.resize(capacity_, DistIndex(std::numeric_limits<DistanceType>::max(),-1));
00111         clear();
00112     }
00113 
00114     ~KNNSimpleResultSet()
00115     {
00116     }
00117 
00121     void clear()
00122     {
00123         worst_distance_ = std::numeric_limits<DistanceType>::max();
00124         dist_index_[capacity_-1].dist_ = worst_distance_;
00125         count_ = 0;
00126     }
00127 
00132     size_t size() const
00133     {
00134         return count_;
00135     }
00136 
00141     bool full() const
00142     {
00143         return count_==capacity_;
00144     }
00145 
00151     void addPoint(DistanceType dist, size_t index)
00152     {
00153         if (dist>=worst_distance_) return;
00154 
00155         if (count_ < capacity_) ++count_;
00156         size_t i;
00157         for (i=count_-1; i>0; --i) {
00158 #ifdef FLANN_FIRST_MATCH
00159             if ( (dist_index_[i-1].dist_>dist) || ((dist==dist_index_[i-1].dist_)&&(dist_index_[i-1].index_>index)) )
00160 #else
00161             if (dist_index_[i-1].dist_>dist)
00162 #endif
00163             {
00164                 dist_index_[i] = dist_index_[i-1];
00165             }
00166             else break;
00167         }
00168         dist_index_[i].dist_ = dist;
00169         dist_index_[i].index_ = index;
00170         worst_distance_ = dist_index_[capacity_-1].dist_;
00171     }
00172 
00180     void copy(size_t* indices, DistanceType* dists, size_t num_elements, bool sorted = true)
00181     {
00182         size_t n = std::min(count_, num_elements);
00183         for (size_t i=0; i<n; ++i) {
00184                 *indices++ = dist_index_[i].index_;
00185                 *dists++ = dist_index_[i].dist_;
00186         }
00187     }
00188 
00189     DistanceType worstDist() const
00190     {
00191         return worst_distance_;
00192     }
00193 
00194 private:
00195     size_t capacity_;
00196     size_t count_;
00197     DistanceType worst_distance_;
00198     std::vector<DistIndex> dist_index_;
00199 };
00200 
00204 template <typename DistanceType>
00205 class KNNResultSet : public ResultSet<DistanceType>
00206 {
00207 public:
00208         typedef DistanceIndex<DistanceType> DistIndex;
00209 
00210     KNNResultSet(int capacity) : capacity_(capacity)
00211     {
00212                 // reserving capacity to prevent memory re-allocations
00213                 dist_index_.resize(capacity_, DistIndex(std::numeric_limits<DistanceType>::max(),-1));
00214         clear();
00215     }
00216 
00217     ~KNNResultSet()
00218     {
00219 
00220     }
00221 
00225     void clear()
00226     {
00227         worst_distance_ = std::numeric_limits<DistanceType>::max();
00228         dist_index_[capacity_-1].dist_ = worst_distance_;
00229         count_ = 0;
00230     }
00231 
00232     size_t size() const
00233     {
00234         return count_;
00235     }
00236 
00237     bool full() const
00238     {
00239         return count_ == capacity_;
00240     }
00241 
00242 
00243     void addPoint(DistanceType dist, size_t index)
00244     {
00245         if (dist >= worst_distance_) return;
00246         size_t i;
00247         for (i = count_; i > 0; --i) {
00248 #ifdef FLANN_FIRST_MATCH
00249             if ( (dist_index_[i-1].dist_<=dist) && ((dist!=dist_index_[i-1].dist_)||(dist_index_[i-1].index_<=index)) )
00250 #else
00251             if (dist_index_[i-1].dist_<=dist)
00252 #endif
00253             {
00254                 // Check for duplicate indices
00255                 for (size_t j = i - 1; dist_index_[j].dist_ == dist && j--;) {
00256                     if (dist_index_[j].index_ == index) {
00257                         return;
00258                     }
00259                 }
00260                 break;
00261             }
00262         }
00263         if (count_ < capacity_) ++count_;
00264         for (size_t j = count_-1; j > i; --j) {
00265             dist_index_[j] = dist_index_[j-1];
00266         }
00267         dist_index_[i].dist_ = dist;
00268         dist_index_[i].index_ = index;
00269         worst_distance_ = dist_index_[capacity_-1].dist_;
00270     }
00271 
00279     void copy(size_t* indices, DistanceType* dists, size_t num_elements, bool sorted = true)
00280     {
00281         size_t n = std::min(count_, num_elements);
00282         for (size_t i=0; i<n; ++i) {
00283                 *indices++ = dist_index_[i].index_;
00284                 *dists++ = dist_index_[i].dist_;
00285         }
00286     }
00287 
00288     DistanceType worstDist() const
00289     {
00290         return worst_distance_;
00291     }
00292 
00293 private:
00294     size_t capacity_;
00295     size_t count_;
00296     DistanceType worst_distance_;
00297     std::vector<DistIndex> dist_index_;
00298 
00299 };
00300 
00301 
00302 
00303 template <typename DistanceType>
00304 class KNNResultSet2 : public ResultSet<DistanceType>
00305 {
00306 public:
00307         typedef DistanceIndex<DistanceType> DistIndex;
00308 
00309         KNNResultSet2(size_t capacity_) :
00310         capacity_(capacity_)
00311     {
00312                 // reserving capacity to prevent memory re-allocations
00313                 dist_index_.reserve(capacity_);
00314         clear();
00315     }
00316 
00317     ~KNNResultSet2()
00318     {
00319     }
00320 
00324     void clear()
00325     {
00326         dist_index_.clear();
00327         worst_dist_ = std::numeric_limits<DistanceType>::max();
00328         is_full_ = false;
00329     }
00330 
00335     size_t size() const
00336     {
00337         return dist_index_.size();
00338     }
00339 
00344     bool full() const
00345     {
00346         return is_full_;
00347     }
00348 
00355     void addPoint(DistanceType dist, size_t index)
00356     {
00357         if (dist>=worst_dist_) return;
00358 
00359         if (dist_index_.size()==capacity_) {
00360                 // if result set if filled to capacity, remove farthest element
00361                 std::pop_heap(dist_index_.begin(), dist_index_.end());
00362                 dist_index_.pop_back();
00363         }
00364 
00365         // add new element
00366         dist_index_.push_back(DistIndex(dist,index));
00367         if (is_full_) { // when is_full_==true, we have a heap
00368                 std::push_heap(dist_index_.begin(), dist_index_.end());
00369         }
00370 
00371         if (dist_index_.size()==capacity_) {
00372                 if (!is_full_) {
00373                         std::make_heap(dist_index_.begin(), dist_index_.end());
00374                 is_full_ = true;
00375                 }
00376                 // we replaced the farthest element, update worst distance
00377                 worst_dist_ = dist_index_[0].dist_;
00378         }
00379     }
00380 
00388     void copy(size_t* indices, DistanceType* dists, size_t num_elements, bool sorted = true)
00389     {
00390         if (sorted) {
00391                 // std::sort_heap(dist_index_.begin(), dist_index_.end());
00392                 // sort seems faster here, even though dist_index_ is a heap
00393                 std::sort(dist_index_.begin(), dist_index_.end());
00394         }
00395         else {
00396                 if (num_elements<size()) {
00397                         std::nth_element(dist_index_.begin(), dist_index_.begin()+num_elements, dist_index_.end());
00398                 }
00399         }
00400 
00401         size_t n = std::min(dist_index_.size(), num_elements);
00402         for (size_t i=0; i<n; ++i) {
00403                 *indices++ = dist_index_[i].index_;
00404                 *dists++ = dist_index_[i].dist_;
00405         }
00406     }
00407 
00408     DistanceType worstDist() const
00409     {
00410         return worst_dist_;
00411     }
00412 
00413 private:
00414     size_t capacity_;
00415     DistanceType worst_dist_;
00416     std::vector<DistIndex> dist_index_;
00417     bool is_full_;
00418 };
00419 
00420 
00425 template <typename DistanceType>
00426 class RadiusResultSet : public ResultSet<DistanceType>
00427 {
00428 public:
00429         typedef DistanceIndex<DistanceType> DistIndex;
00430 
00431         RadiusResultSet(DistanceType radius_) :
00432         radius_(radius_)
00433     {
00434                 // reserving some memory to limit number of re-allocations
00435                 dist_index_.reserve(1024);
00436         clear();
00437     }
00438 
00439     ~RadiusResultSet()
00440     {
00441     }
00442 
00446     void clear()
00447     {
00448         dist_index_.clear();
00449     }
00450 
00455     size_t size() const
00456     {
00457         return dist_index_.size();
00458     }
00459 
00464     bool full() const
00465     {
00466         return true;
00467     }
00468 
00475     void addPoint(DistanceType dist, size_t index)
00476     {
00477         if (dist<radius_) {
00478                 // add new element
00479                 dist_index_.push_back(DistIndex(dist,index));
00480         }
00481     }
00482 
00490     void copy(size_t* indices, DistanceType* dists, size_t num_elements, bool sorted = true)
00491     {
00492         if (sorted) {
00493                 // std::sort_heap(dist_index_.begin(), dist_index_.end());
00494                 // sort seems faster here, even though dist_index_ is a heap
00495                 std::sort(dist_index_.begin(), dist_index_.end());
00496         }
00497         else {
00498                 if (num_elements<size()) {
00499                         std::nth_element(dist_index_.begin(), dist_index_.begin()+num_elements, dist_index_.end());
00500                 }
00501         }
00502 
00503         size_t n = std::min(dist_index_.size(), num_elements);
00504         for (size_t i=0; i<n; ++i) {
00505                 *indices++ = dist_index_[i].index_;
00506                 *dists++ = dist_index_[i].dist_;
00507         }
00508     }
00509 
00510     DistanceType worstDist() const
00511     {
00512         return radius_;
00513     }
00514 
00515 private:
00516     DistanceType radius_;
00517     std::vector<DistIndex> dist_index_;
00518 };
00519 
00520 
00521 
00526 template <typename DistanceType>
00527 class KNNRadiusResultSet : public ResultSet<DistanceType>
00528 {
00529 public:
00530         typedef DistanceIndex<DistanceType> DistIndex;
00531 
00532         KNNRadiusResultSet(DistanceType radius_, size_t capacity_) :
00533         radius_(radius_), capacity_(capacity_)
00534     {
00535                 // reserving capacity to prevent memory re-allocations
00536                 dist_index_.reserve(capacity_);
00537         clear();
00538     }
00539 
00540     ~KNNRadiusResultSet()
00541     {
00542     }
00543 
00547     void clear()
00548     {
00549         dist_index_.clear();
00550         worst_dist_ = radius_;
00551         is_heap_ = false;
00552     }
00553 
00558     size_t size() const
00559     {
00560         return dist_index_.size();
00561     }
00562 
00567     bool full() const
00568     {
00569         return true;
00570     }
00571 
00578     void addPoint(DistanceType dist, size_t index)
00579     {
00580         if (dist>=worst_dist_) return;
00581 
00582         if (dist_index_.size()==capacity_) {
00583                 // if result set is filled to capacity, remove farthest element
00584                 std::pop_heap(dist_index_.begin(), dist_index_.end());
00585                 dist_index_.pop_back();
00586         }
00587 
00588         // add new element
00589         dist_index_.push_back(DistIndex(dist,index));
00590         if (is_heap_) {
00591                 std::push_heap(dist_index_.begin(), dist_index_.end());
00592         }
00593 
00594         if (dist_index_.size()==capacity_) {
00595                 // when got to full capacity, make it a heap
00596                 if (!is_heap_) {
00597                         std::make_heap(dist_index_.begin(), dist_index_.end());
00598                         is_heap_ = true;
00599                 }
00600                 // we replaced the farthest element, update worst distance
00601                 worst_dist_ = dist_index_[0].dist_;
00602         }
00603     }
00604 
00612     void copy(size_t* indices, DistanceType* dists, size_t num_elements, bool sorted = true)
00613     {
00614         if (sorted) {
00615                 // std::sort_heap(dist_index_.begin(), dist_index_.end());
00616                 // sort seems faster here, even though dist_index_ is a heap
00617                 std::sort(dist_index_.begin(), dist_index_.end());
00618         }
00619         else {
00620                 if (num_elements<size()) {
00621                         std::nth_element(dist_index_.begin(), dist_index_.begin()+num_elements, dist_index_.end());
00622                 }
00623         }
00624 
00625         size_t n = std::min(dist_index_.size(), num_elements);
00626         for (size_t i=0; i<n; ++i) {
00627                 *indices++ = dist_index_[i].index_;
00628                 *dists++ = dist_index_[i].dist_;
00629         }
00630     }
00631 
00632     DistanceType worstDist() const
00633     {
00634         return worst_dist_;
00635     }
00636 
00637 private:
00638     bool is_heap_;
00639     DistanceType radius_;
00640     size_t capacity_;
00641     DistanceType worst_dist_;
00642     std::vector<DistIndex> dist_index_;
00643 };
00644 
00645 
00647 
00651 template <typename DistanceType>
00652 class CountRadiusResultSet : public ResultSet<DistanceType>
00653 {
00654     DistanceType radius;
00655     size_t count;
00656 
00657 public:
00658     CountRadiusResultSet(DistanceType radius_ ) :
00659         radius(radius_)
00660     {
00661         clear();
00662     }
00663 
00664     ~CountRadiusResultSet()
00665     {
00666     }
00667 
00668     void clear()
00669     {
00670         count = 0;
00671     }
00672 
00673     size_t size() const
00674     {
00675         return count;
00676     }
00677 
00678     bool full() const
00679     {
00680         return true;
00681     }
00682 
00683     void addPoint(DistanceType dist, size_t index)
00684     {
00685         if (dist<radius) {
00686             count++;
00687         }
00688     }
00689 
00690     DistanceType worstDist() const
00691     {
00692         return radius;
00693     }
00694 
00695 };
00696 
00697 
00698 
00700 
00703 template<typename DistanceType>
00704 class UniqueResultSet : public ResultSet<DistanceType>
00705 {
00706 public:
00707     struct DistIndex
00708     {
00709         DistIndex(DistanceType dist, unsigned int index) :
00710             dist_(dist), index_(index)
00711         {
00712         }
00713         bool operator<(const DistIndex dist_index) const
00714         {
00715             return (dist_ < dist_index.dist_) || ((dist_ == dist_index.dist_) && index_ < dist_index.index_);
00716         }
00717         DistanceType dist_;
00718         unsigned int index_;
00719     };
00720 
00722     UniqueResultSet() :
00723         worst_distance_(std::numeric_limits<DistanceType>::max())
00724     {
00725     }
00726 
00730     inline bool full() const
00731     {
00732         return is_full_;
00733     }
00734 
00740     void copy(size_t* indices, DistanceType* dist, int n_neighbors, bool sorted = true)
00741     {
00742         if (n_neighbors<0) n_neighbors = dist_indices_.size();
00743         int i = 0;
00744         typedef typename std::set<DistIndex>::const_iterator Iterator;
00745         for (Iterator dist_index = dist_indices_.begin(), dist_index_end =
00746                         dist_indices_.end(); (dist_index != dist_index_end) && (i < n_neighbors); ++dist_index, ++indices, ++dist, ++i) {
00747                 *indices = dist_index->index_;
00748                 *dist = dist_index->dist_;
00749         }
00750     }
00751 
00755     size_t size() const
00756     {
00757         return dist_indices_.size();
00758     }
00759 
00764     inline DistanceType worstDist() const
00765     {
00766         return worst_distance_;
00767     }
00768 protected:
00770     bool is_full_;
00771 
00773     DistanceType worst_distance_;
00774 
00776     std::set<DistIndex> dist_indices_;
00777 };
00778 
00780 
00784 template<typename DistanceType>
00785 class KNNUniqueResultSet : public UniqueResultSet<DistanceType>
00786 {
00787 public:
00791     KNNUniqueResultSet(unsigned int capacity) : capacity_(capacity)
00792     {
00793         this->is_full_ = false;
00794         this->clear();
00795     }
00796 
00801     inline void addPoint(DistanceType dist, size_t index)
00802     {
00803         // Don't do anything if we are worse than the worst
00804         if (dist >= worst_distance_) return;
00805         dist_indices_.insert(DistIndex(dist, index));
00806 
00807         if (is_full_) {
00808             if (dist_indices_.size() > capacity_) {
00809                 dist_indices_.erase(*dist_indices_.rbegin());
00810                 worst_distance_ = dist_indices_.rbegin()->dist_;
00811             }
00812         }
00813         else if (dist_indices_.size() == capacity_) {
00814             is_full_ = true;
00815             worst_distance_ = dist_indices_.rbegin()->dist_;
00816         }
00817     }
00818 
00821     void clear()
00822     {
00823         dist_indices_.clear();
00824         worst_distance_ = std::numeric_limits<DistanceType>::max();
00825         is_full_ = false;
00826     }
00827 
00828 protected:
00829     typedef typename UniqueResultSet<DistanceType>::DistIndex DistIndex;
00830     using UniqueResultSet<DistanceType>::is_full_;
00831     using UniqueResultSet<DistanceType>::worst_distance_;
00832     using UniqueResultSet<DistanceType>::dist_indices_;
00833 
00835     unsigned int capacity_;
00836 };
00837 
00839 
00843 template<typename DistanceType>
00844 class RadiusUniqueResultSet : public UniqueResultSet<DistanceType>
00845 {
00846 public:
00850     RadiusUniqueResultSet(DistanceType radius) :
00851         radius_(radius)
00852     {
00853         is_full_ = true;
00854     }
00855 
00860     void addPoint(DistanceType dist, size_t index)
00861     {
00862         if (dist < radius_) dist_indices_.insert(DistIndex(dist, index));
00863     }
00864 
00867     inline void clear()
00868     {
00869         dist_indices_.clear();
00870     }
00871 
00872 
00876     inline bool full() const
00877     {
00878         return true;
00879     }
00880 
00885     inline DistanceType worstDist() const
00886     {
00887         return radius_;
00888     }
00889 private:
00890     typedef typename UniqueResultSet<DistanceType>::DistIndex DistIndex;
00891     using UniqueResultSet<DistanceType>::dist_indices_;
00892     using UniqueResultSet<DistanceType>::is_full_;
00893 
00895     DistanceType radius_;
00896 };
00897 
00899 
00902 template<typename DistanceType>
00903 class KNNRadiusUniqueResultSet : public KNNUniqueResultSet<DistanceType>
00904 {
00905 public:
00909     KNNRadiusUniqueResultSet(DistanceType radius, size_t capacity) : KNNUniqueResultSet<DistanceType>(capacity)
00910     {
00911         this->radius_ = radius;
00912         this->clear();
00913     }
00914 
00917     void clear()
00918     {
00919         dist_indices_.clear();
00920         worst_distance_ = radius_;
00921         is_full_ = true;
00922     }
00923 private:
00924     using KNNUniqueResultSet<DistanceType>::dist_indices_;
00925     using KNNUniqueResultSet<DistanceType>::is_full_;
00926     using KNNUniqueResultSet<DistanceType>::worst_distance_;
00927 
00929     DistanceType radius_;
00930 };
00931 }
00932 
00933 #endif //FLANN_RESULTSET_H
00934 


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