helpers.h
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 #ifndef __NABE_TEST_HELPERS_H
00033 #define __NABE_TEST_HELPERS_H
00034 
00035 #include "nabo/nabo.h"
00036 #include <chrono>
00037 #include <limits>
00038 #include <iostream>
00039 #include <fstream>
00040 
00041 #include <cstdint>
00042 
00043 using namespace std;
00044 using namespace Nabo;
00045 
00046 template<typename T>
00047 typename NearestNeighbourSearch<T>::Matrix load(const char *fileName)
00048 {
00049         typedef typename NearestNeighbourSearch<T>::Matrix Matrix;
00050         
00051         ifstream ifs(fileName);
00052         if (!ifs.good())
00053         {
00054                 cerr << "Cannot open file "<< fileName << endl;
00055                 exit(1);
00056         }
00057         
00058         vector<T> data;
00059         int dim(0);
00060         bool firstLine(true);
00061         
00062         while (!ifs.eof())
00063         {
00064                 char line[1024];
00065                 ifs.getline(line, sizeof(line));
00066                 line[sizeof(line)-1] = 0;
00067                 
00068                 char *token = strtok(line, " \t,;");
00069                 while (token)
00070                 {
00071                         if (firstLine)
00072                                 ++dim;
00073                         data.push_back(atof(token));
00074                         token = strtok(NULL, " \t,;"); // FIXME: non reentrant, use strtok_r
00075                 }
00076                 firstLine = false;
00077         }
00078         
00079         return Matrix::Map(&data[0], dim, data.size() / dim);
00080 }
00081 
00082 template<typename T>
00083 typename NearestNeighbourSearch<T>::Vector createQuery(const typename NearestNeighbourSearch<T>::Matrix& d, const NearestNeighbourSearch<T>& kdt, const int i, const int method)
00084 {
00085         typedef typename NearestNeighbourSearch<T>::Vector VectorT;
00086         if (method < 0)
00087         {
00088                 VectorT q = d.col(i % d.cols());
00089                 T absBound = 0;
00090                 for (int j = 0; j < q.size(); ++j)
00091                         absBound += kdt.maxBound(j) - kdt.minBound(j);
00092                 absBound /= (-method); // divided by -method
00093 #ifdef EIGEN3_API
00094                 if (i < d.cols())
00095                         q.array() += absBound;
00096                 else
00097                         q.array() -= absBound;
00098 #else // EIGEN3_API
00099                 if (i < d.cols())
00100                         q.cwise() += absBound;
00101                 else
00102                         q.cwise() -= absBound;
00103 #endif // EIGEN3_API
00104                 return q;
00105         }
00106         else
00107         {
00108                 VectorT q(kdt.minBound.size());
00109                 for (int j = 0; j < q.size(); ++j)
00110                         q(j) = kdt.minBound(j) + T(rand()) * (kdt.maxBound(j) - kdt.minBound(j)) / T(RAND_MAX);
00111                 return q;
00112         }
00113 }
00114 
00115 template<typename T>
00116 typename NearestNeighbourSearch<T>::Matrix createQuery(const typename NearestNeighbourSearch<T>::Matrix& d, const int itCount, const int method)
00117 {
00118         typedef typename NearestNeighbourSearch<T>::Matrix MatrixT;
00119         typedef Nabo::NearestNeighbourSearch<T> NNS;
00120         NNS* nns = NNS::create(d, d.rows(), typename NNS::SearchType(0));
00121         MatrixT q(d.rows(), itCount);
00122         for (int i = 0; i < itCount; ++i)
00123                 q.col(i) = createQuery<T>(d, *nns, i, method);
00124         delete nns;
00125         return q;
00126 }
00127 
00128 struct timer
00129 {
00130         using Clock = std::chrono::high_resolution_clock;
00131         using Time = Clock::time_point;
00132 
00133         timer():_start_time(curTime()){ }
00134         void restart() { _start_time = curTime(); }
00135         double elapsed() const                  // return elapsed time in seconds
00136         { 
00137                 using namespace std::chrono;
00138                 return duration_cast<duration<double>>(curTime() - _start_time).count();
00139         }
00140 
00141 private:
00142         Time curTime() const {
00143                 return Clock::now();
00144         }
00145         Time _start_time;
00146 };
00147 
00148 #endif // __NABE_TEST_HELPERS_H
00149 
00150 /* vim: set ts=8 sw=8 tw=0 noexpandtab cindent softtabstop=8 :*/


libnabo
Author(s): Stéphane Magnenat
autogenerated on Sun Feb 10 2019 03:52:20