knnbench.cpp
Go to the documentation of this file.
00001 /*
00002 
00003 Copyright (c) 2010--2011, Stephane Magnenat, ASL, ETHZ, Switzerland
00004 You can contact the author at <stephane at magnenat dot net>
00005 
00006 All rights reserved.
00007 
00008 Redistribution and use in source and binary forms, with or without
00009 modification, are permitted provided that the following conditions are met:
00010     * Redistributions of source code must retain the above copyright
00011       notice, this list of conditions and the following disclaimer.
00012     * Redistributions in binary form must reproduce the above copyright
00013       notice, this list of conditions and the following disclaimer in the
00014       documentation and/or other materials provided with the distribution.
00015     * Neither the name of the <organization> nor the
00016       names of its contributors may be used to endorse or promote products
00017       derived from this software without specific prior written permission.
00018 
00019 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00020 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00021 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00022 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
00023 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00024 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00026 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00027 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00028 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00029 
00030 */
00031 
00032 // currently disable FLANN
00033 #undef HAVE_FLANN
00034 
00035 #include "nabo/nabo.h"
00036 #include "experimental/nabo_experimental.h"
00037 #include "helpers.h"
00038 #ifdef HAVE_ANN
00039         #include "ANN.h"
00040 #endif // HAVE_ANN
00041 #ifdef HAVE_FLANN
00042         #include "flann/flann.hpp"
00043 #endif // HAVE_FLANN
00044 #include <iostream>
00045 #include <fstream>
00046 #include <stdexcept>
00047 
00048 using namespace std;
00049 using namespace Nabo;
00050 
00051 typedef Nabo::NearestNeighbourSearch<double>::Matrix MatrixD;
00052 typedef Nabo::NearestNeighbourSearch<double>::Vector VectorD;
00053 typedef Nabo::NearestNeighbourSearch<double>::Index IndexD;
00054 typedef Nabo::NearestNeighbourSearch<double>::IndexVector IndexVectorD;
00055 typedef Nabo::NearestNeighbourSearch<float>::Matrix MatrixF;
00056 typedef Nabo::NearestNeighbourSearch<float>::Vector VectorF;
00057 typedef Nabo::NearestNeighbourSearch<float>::Index IndexF;
00058 typedef Nabo::NearestNeighbourSearch<float>::IndexVector IndexVectorF;
00059 typedef Nabo::BruteForceSearch<double> BFSD;
00060 typedef Nabo::BruteForceSearch<float> BFSF;
00061 // typedef Nabo::KDTreeBalancedPtInNodesPQ<double> KDTD1;
00062 // typedef Nabo::KDTreeBalancedPtInNodesStack<double> KDTD2;
00063 // struct KDTD3: public Nabo::KDTreeBalancedPtInLeavesStack<double>
00064 // {
00065 //      KDTD3(const Matrix& cloud):
00066 //              Nabo::KDTreeBalancedPtInLeavesStack<double>(cloud, true)
00067 //      {}
00068 // };
00069 // struct KDTD4: public Nabo::KDTreeBalancedPtInLeavesStack<double>
00070 // {
00071 //      KDTD4(const Matrix& cloud):
00072 //              Nabo::KDTreeBalancedPtInLeavesStack<double>(cloud, false)
00073 //      {}
00074 // };
00075 // typedef Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStack<double,IndexHeapSTL<int,double>> KDTD5A;
00076 // typedef Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStack<double,IndexHeapBruteForceVector<int,double>> KDTD5B;
00077 // typedef Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt<double,IndexHeapBruteForceVector<int,double>> KDTD5OB;
00078 // typedef Nabo::KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt<double,IndexHeapSTL<int,double>> KDTD5OA;
00079 // typedef Nabo::KDTreeUnbalancedPtInLeavesExplicitBoundsStack<double> KDTD6;
00080 
00081 
00082 
00083 
00084 struct BenchResult
00085 {
00086         double creationDuration;
00087         double executionDuration;
00088         double visitCount;
00089         double totalCount;
00090         
00091         BenchResult():
00092                 creationDuration(0),
00093                 executionDuration(0),
00094                 visitCount(0),
00095                 totalCount(0)
00096         {}
00097         
00098         void operator +=(const BenchResult& that)
00099         {
00100                 creationDuration += that.creationDuration;
00101                 executionDuration += that.executionDuration;
00102                 visitCount += that.visitCount;
00103                 totalCount += that.totalCount;
00104         }
00105         
00106         void operator /=(const double factor)
00107         {
00108                 creationDuration /= factor;
00109                 executionDuration /= factor;
00110                 visitCount /= factor;
00111                 totalCount /= factor;
00112         }
00113 };
00114 typedef vector<BenchResult> BenchResults;
00115 
00116 // template<typename T>
00117 // BenchResult doBench(const Matrix& d, const Matrix& q, const Index K, const int itCount)
00118 // {
00119 //      BenchResult result;
00120 //      boost::timer t;
00121 //      T nns(d);
00122 //      result.creationDuration = t.elapsed();
00123 //      
00124 //      t.restart();
00125 //      nns.knnM(q, K, 0, 0);
00126 //      result.executionDuration = t.elapsed();
00127 //      
00128 //      result.visitCount = double(nns.getStatistics().totalVisitCount);
00129 //      result.totalCount = double(itCount) * double(d.cols());
00130 //      
00131 //      return result;
00132 // }
00133 
00134 template<typename T>
00135 BenchResult doBenchType(const typename NearestNeighbourSearch<T>::SearchType type, 
00136                                                 const unsigned creationOptionFlags,
00137                                                 const typename NearestNeighbourSearch<T>::Matrix& d,
00138                                                 const typename NearestNeighbourSearch<T>::Matrix& q,
00139                                                 const int K,
00140                                                 const int /*itCount*/,
00141                                                 const int searchCount)
00142 {
00143         typedef NearestNeighbourSearch<T> nnsT;
00144         typedef typename NearestNeighbourSearch<T>::Matrix Matrix;
00145         typedef typename NearestNeighbourSearch<T>::IndexMatrix IndexMatrix;
00146         
00147         BenchResult result;
00148         boost::timer t;
00149         nnsT* nns(nnsT::create(d, d.rows(), type, creationOptionFlags));
00150         result.creationDuration = t.elapsed();
00151         
00152         for (int s = 0; s < searchCount; ++s)
00153         {
00154                 t.restart();
00155                 IndexMatrix indices(K, q.cols());
00156                 Matrix dists2(K, q.cols());
00157                 const unsigned long visitCount = nns->knn(q, indices, dists2, K, 0, 0);
00158                 result.executionDuration += t.elapsed();
00159                 result.visitCount += double(visitCount);
00160         }
00161         result.executionDuration /= double(searchCount);
00162         result.visitCount /= double(searchCount);
00163         
00164         delete nns;
00165         
00166         result.totalCount = double(q.cols()) * double(d.cols());
00167         
00168         return result;
00169 }
00170 
00171 #ifdef HAVE_ANN
00172 
00173 BenchResult doBenchANNStack(const MatrixD& d, const MatrixD& q, const int K, const int itCount, const int searchCount)
00174 {
00175         BenchResult result;
00176         boost::timer t;
00177         const int ptCount(d.cols());
00178         const double **pa = new const double *[d.cols()];
00179         for (int i = 0; i < ptCount; ++i)
00180                 pa[i] = &d.coeff(0, i);
00181         ANNkd_tree* ann_kdt = new ANNkd_tree(const_cast<double**>(pa), ptCount, d.rows(), 8);
00182         result.creationDuration = t.elapsed();
00183         
00184         for (int s = 0; s < searchCount; ++s)
00185         {
00186                 t.restart();
00187                 ANNidx nnIdx[K];
00188                 ANNdist dists[K];
00189                 for (int i = 0; i < itCount; ++i)
00190                 {
00191                         const VectorD& tq(q.col(i));
00192                         ANNpoint queryPt(const_cast<double*>(&tq.coeff(0)));
00193                         ann_kdt->annkSearch(            // search
00194                                                         queryPt,        // query point
00195                                                         K,                      // number of near neighbours
00196                                                         nnIdx,          // nearest neighbours (returned)
00197                                                         dists,          // distance (returned)
00198                                                         0);                     // error bound
00199                 }
00200                 result.executionDuration += t.elapsed();
00201         }
00202         result.executionDuration /= double(searchCount);
00203         
00204         return result;
00205 }
00206 
00207 BenchResult doBenchANNPriority(const MatrixD& d, const MatrixD& q, const int K, const int itCount, const int searchCount)
00208 {
00209         BenchResult result;
00210         boost::timer t;
00211         const int ptCount(d.cols());
00212         const double **pa = new const double *[d.cols()];
00213         for (int i = 0; i < ptCount; ++i)
00214                 pa[i] = &d.coeff(0, i);
00215         ANNkd_tree* ann_kdt = new ANNkd_tree(const_cast<double**>(pa), ptCount, d.rows(), 8);
00216         result.creationDuration = t.elapsed();
00217         
00218         for (int s = 0; s < searchCount; ++s)
00219         {
00220                 t.restart();
00221                 ANNidx nnIdx[K];
00222                 ANNdist dists[K];
00223                 for (int i = 0; i < itCount; ++i)
00224                 {
00225                         const VectorD& tq(q.col(i));
00226                         ANNpoint queryPt(const_cast<double*>(&tq.coeff(0)));
00227                         ann_kdt->annkPriSearch(         // search
00228                                                         queryPt,        // query point
00229                                                         K,                      // number of near neighbours
00230                                                         nnIdx,          // nearest neighbours (returned)
00231                                                         dists,          // distance (returned)
00232                                                         0);                     // error bound
00233                 }
00234                 result.executionDuration += t.elapsed();
00235         }
00236         result.executionDuration /= double(searchCount);
00237         
00238         return result;
00239 }
00240 
00241 #endif // HAVE_ANN
00242 
00243 #ifdef HAVE_FLANN
00244 
00245 template<typename T>
00246 BenchResult doBenchFLANN(const Matrix& d, const Matrix& q, const Index K, const int itCount)
00247 {
00248         BenchResult result;
00249         const int dimCount(d.rows());
00250         const int dPtCount(d.cols());
00251         const int qPtCount(itCount);
00252         
00253         flann::Matrix<T> dataset(new T[dPtCount*dimCount], dPtCount, dimCount);
00254         for (int point = 0; point < dPtCount; ++point)
00255                 for (int dim = 0; dim < dimCount; ++dim)
00256                         dataset[point][dim] = d(dim, point);
00257                 flann::Matrix<T> query(new T[qPtCount*dimCount], qPtCount, dimCount);
00258         for (int point = 0; point < qPtCount; ++point)
00259                 for (int dim = 0; dim < dimCount; ++dim)
00260                         query[point][dim] = q(dim, point);
00261         
00262         flann::Matrix<int> indices(new int[query.rows*K], query.rows, K);
00263         flann::Matrix<float> dists(new float[query.rows*K], query.rows, K);
00264         
00265         // construct an randomized kd-tree index using 4 kd-trees
00266         boost::timer t;
00267         flann::Index<T> index(dataset, flann::KDTreeIndexParams(4) /*flann::AutotunedIndexParams(0.9)*/); // exact search
00268         index.buildIndex();
00269         result.creationDuration = t.elapsed();
00270         
00271         t.restart();
00272         // do a knn search, using 128 checks
00273         index.knnSearch(query, indices, dists, int(K), flann::SearchParams(128)); // last parameter ignored because of autotuned
00274         result.executionDuration = t.elapsed();
00275         
00276         dataset.free();
00277         query.free();
00278         indices.free();
00279         dists.free();
00280         
00281         return result;
00282 }
00283 
00284 #endif // HAVE_FLANN
00285 
00286 
00287 int main(int argc, char* argv[])
00288 {
00289         if (argc != 6)
00290         {
00291                 cerr << "Usage " << argv[0] << " DATA K METHOD RUN_COUNT SEARCH_COUNT" << endl;
00292                 return 1;
00293         }
00294         
00295         const MatrixD dD(load<double>(argv[1]));
00296         const MatrixF dF(load<float>(argv[1]));
00297         const int K(atoi(argv[2]));
00298         const int method(atoi(argv[3]));
00299         const int itCount(method >= 0 ? method : dD.cols() * 2);
00300         const int runCount(atoi(argv[4]));
00301         const int searchCount(atoi(argv[5]));
00302         
00303         // compare KDTree with brute force search
00304         if (K >= dD.cols())
00305         {
00306                 cerr << "Requested more nearest neighbour than points in the data set" << endl;
00307                 return 2;
00308         }
00309         
00310         // create queries
00311         MatrixD qD(createQuery<double>(dD, itCount, method));
00312         MatrixF qF(createQuery<float>(dF, itCount, method));
00313         
00314         const char* benchLabels[] =
00315         {
00316                 //doBench<KDTD1>("Nabo, pt in nodes, priority, balance variance",
00317                 //doBench<KDTD2>("Nabo, pt in nodes, stack, balance variance",
00318                 //doBench<KDTD3>("Nabo, balanced, stack, pt in leaves only, balance variance",
00319                 //"Nabo, balanced, stack, pt in leaves only, balance cell aspect ratio",
00320                 //"Nabo, unbalanced, stack, pt in leaves only, implicit bounds, ANN_KD_SL_MIDPT, STL heap",
00321                 //"Nabo, unbalanced, stack, pt in leaves only, implicit bounds, ANN_KD_SL_MIDPT, brute-force vector heap",
00322                 "Nabo, double, unbalanced, stack, pt in leaves only, implicit bounds, ANN_KD_SL_MIDPT, brute-force vector heap, opt",
00323                 "Nabo, double, unbalanced, stack, pt in leaves only, implicit bounds, ANN_KD_SL_MIDPT, STL heap, opt",
00324                 "Nabo, float, unbalanced, stack, pt in leaves only, implicit bounds, ANN_KD_SL_MIDPT, brute-force vector heap, opt",
00325                 "Nabo, float, unbalanced, stack, pt in leaves only, implicit bounds, ANN_KD_SL_MIDPT, STL heap, opt",
00326                 "Nabo, float, unbalanced, stack, pt in leaves only, implicit bounds, ANN_KD_SL_MIDPT, STL heap, opt, stats",
00327                 #ifdef HAVE_OPENCL
00328                 "Nabo, float, OpenCL, GPU, balanced, points in nodes, stack, implicit bounds, balance aspect ratio, stats",
00329                 "Nabo, float, OpenCL, GPU, balanced, points in leaves, stack, implicit bounds, balance aspect ratio, stats",
00330                 //"Nabo, float, OpenCL, GPU, brute force",
00331                 #endif // HAVE_OPENCL
00332                 //"Nabo, unbalanced, points in leaves, stack, explicit bounds, ANN_KD_SL_MIDPT",
00333                 #ifdef HAVE_ANN
00334                 "ANN stack, double",
00335                 //"ANN priority",
00336                 #endif // HAVE_ANN
00337                 #ifdef HAVE_FLANN
00338                 "FLANN, double",
00339                 "FLANN, float",
00340                 #endif // HAVE_FLANN
00341         };
00342         
00343         // do bench themselves, accumulate over several times
00344         size_t benchCount(sizeof(benchLabels) / sizeof(const char *));
00345         cout << "Doing " << benchCount << " different benches " << runCount << " times, with " << searchCount << " query per run" << endl;
00346         BenchResults results(benchCount);
00347         for (int run = 0; run < runCount; ++run)
00348         {
00349                 size_t i = 0;
00350                 //results.at(i++) += doBench<KDTD1>(d, q, K, itCount, searchCount);
00351                 //results.at(i++) += doBench<KDTD2>(d, q, K, itCount, searchCount);
00352                 //results.at(i++) += doBench<KDTD3>(d, q, K, itCount, searchCount);
00353                 //results.at(i++) += doBench<KDTD4>(d, q, K, itCount, searchCount);
00354                 //results.at(i++) += doBench<KDTD5A>(d, q, K, itCount, searchCount);
00355                 //results.at(i++) += doBench<KDTD5B>(d, q, K, itCount, searchCount);
00356                 results.at(i++) += doBenchType<double>(NNSearchD::KDTREE_LINEAR_HEAP, 0, dD, qD, K, itCount, searchCount);
00357                 results.at(i++) += doBenchType<double>(NNSearchD::KDTREE_TREE_HEAP, 0, dD, qD, K, itCount, searchCount);
00358                 results.at(i++) += doBenchType<float>(NNSearchF::KDTREE_LINEAR_HEAP, 0, dF, qF, K, itCount, searchCount);
00359                 results.at(i++) += doBenchType<float>(NNSearchF::KDTREE_TREE_HEAP, 0, dF, qF, K, itCount, searchCount);
00360                 results.at(i++) += doBenchType<float>(NNSearchF::KDTREE_TREE_HEAP, NNSearchF::TOUCH_STATISTICS, dF, qF, K, itCount, searchCount);
00361                 #ifdef HAVE_OPENCL
00362                 results.at(i++) += doBenchType<float>(NNSearchF::KDTREE_CL_PT_IN_NODES, NNSearchF::TOUCH_STATISTICS, dF, qF, K, itCount, searchCount);
00363                 results.at(i++) += doBenchType<float>(NNSearchF::KDTREE_CL_PT_IN_LEAVES, NNSearchF::TOUCH_STATISTICS, dF, qF, K, itCount, searchCount);
00364                 //results.at(i++) += doBenchType<float>(NNSearchF::BRUTE_FORCE_CL, dF, qF, K, itCount, searchCount);
00365                 #endif // HAVE_OPENCL
00366                 #ifdef HAVE_ANN
00367                 results.at(i++) += doBenchANNStack(dD, qD, K, itCount, searchCount);
00368                 //results.at(i++) += doBenchANNPriority(d, q, K, itCount);
00369                 #endif // HAVE_ANN
00370                 #ifdef HAVE_FLANN
00371                 results.at(i++) += doBenchFLANN<double>(dD, qD, K, itCount, searchCount);
00372                 results.at(i++) += doBenchFLANN<float>(dF, qF, K, itCount, searchCount);
00373                 #endif // HAVE_FLANN
00374         }
00375         
00376         // print results
00377         cout << "Showing average over " << runCount << " runs\n\n";
00378         for (size_t i = 0; i < benchCount; ++i)
00379         {
00380                 results[i] /= double(runCount);
00381                 cout << "Method " << benchLabels[i] << ":\n";
00382                 cout << "  creation duration: " << results[i].creationDuration << "\n";
00383                 cout << "  execution duration: " << results[i].executionDuration << "\n";
00384                 if (results[i].totalCount != 0)
00385                 {
00386                         cout << "  visit count: " << results[i].visitCount << "\n";
00387                         cout << "  total count: " << results[i].totalCount << "\n";
00388                         cout << "  precentage visit: " << (results[i].visitCount * 100.) / results[i].totalCount << "\n";
00389                 }
00390                 else
00391                         cout << "  no stats for visits\n";
00392                 cout << endl;
00393         }
00394         
00395         return 0;
00396 }


libnabo
Author(s): Stéphane Magnenat
autogenerated on Thu Sep 10 2015 10:54:55