nabo.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 __NABO_H
00033 #define __NABO_H
00034 
00035 #include "Eigen/Core"
00036 #if EIGEN_VERSION_AT_LEAST(2,92,0)
00037     #define EIGEN3_API
00038 #endif
00039 #ifndef EIGEN3_API
00040     #include "Eigen/Array"
00041 #endif
00042 #include <vector>
00043 #include <map>
00044 #include <boost/any.hpp>
00045 
00206 
00207 namespace Nabo
00208 {
00210 
00211     
00213     #define NABO_VERSION "1.0.1"
00214 
00215     #define NABO_VERSION_INT 10001
00216     
00218     struct Parameters: public std::map<std::string, boost::any>
00219     {
00221         Parameters(){}
00223 
00226         Parameters(const std::string& key, const boost::any& value){(*this)[key] = value;}
00228 
00232         template<typename  T>
00233         T get(const std::string& key, const T& defaultValue) const
00234         {
00235             const_iterator it(find(key));
00236             if (it != end())
00237                 return boost::any_cast<T>(it->second);
00238             else
00239                 return defaultValue;
00240         }
00241     };
00242     
00244     template<typename T>
00245     struct NearestNeighbourSearch
00246     {
00248         typedef typename Eigen::Matrix<T, Eigen::Dynamic, 1> Vector; 
00250         typedef typename Eigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> Matrix;
00252         typedef int Index;
00254         typedef typename Eigen::Matrix<Index, Eigen::Dynamic, 1> IndexVector;
00256         typedef typename Eigen::Matrix<Index, Eigen::Dynamic, Eigen::Dynamic> IndexMatrix;
00257         
00259         const Matrix& cloud;
00261         const Index dim;
00263         const unsigned creationOptionFlags;
00265         const Vector minBound;
00267         const Vector maxBound;
00268         
00270         enum SearchType
00271         {
00272             BRUTE_FORCE = 0, 
00273             KDTREE_LINEAR_HEAP, 
00274             KDTREE_TREE_HEAP, 
00275             KDTREE_CL_PT_IN_NODES, 
00276             KDTREE_CL_PT_IN_LEAVES, 
00277             BRUTE_FORCE_CL, 
00278             SEARCH_TYPE_COUNT 
00279         };
00280         
00282         enum CreationOptionFlags
00283         {
00284             TOUCH_STATISTICS = 1, 
00285         };
00286         
00288         enum SearchOptionFlags
00289         {
00290             ALLOW_SELF_MATCH = 1, 
00291             SORT_RESULTS = 2 
00292         };
00293         
00295 
00305         unsigned long knn(const Vector& query, IndexVector& indices, Vector& dists2, const Index k = 1, const T epsilon = 0, const unsigned optionFlags = 0, const T maxRadius = std::numeric_limits<T>::infinity()) const;
00306         
00308 
00318         virtual unsigned long knn(const Matrix& query, IndexMatrix& indices, Matrix& dists2, const Index k = 1, const T epsilon = 0, const unsigned optionFlags = 0, const T maxRadius = std::numeric_limits<T>::infinity()) const = 0;
00319         
00321 
00331         virtual unsigned long knn(const Matrix& query, IndexMatrix& indices, Matrix& dists2, const Vector& maxRadii, const Index k = 1, const T epsilon = 0, const unsigned optionFlags = 0) const = 0;
00332         
00334 
00340         static NearestNeighbourSearch* create(const Matrix& cloud, const Index dim = std::numeric_limits<Index>::max(), const SearchType preferedType = KDTREE_LINEAR_HEAP, const unsigned creationOptionFlags = 0, const Parameters& additionalParameters = Parameters());
00341         
00343 
00348         static NearestNeighbourSearch* createBruteForce(const Matrix& cloud, const Index dim = std::numeric_limits<Index>::max(), const unsigned creationOptionFlags = 0);
00349         
00351 
00357         static NearestNeighbourSearch* createKDTreeLinearHeap(const Matrix& cloud, const Index dim = std::numeric_limits<Index>::max(), const unsigned creationOptionFlags = 0, const Parameters& additionalParameters = Parameters());
00358         
00360 
00366         static NearestNeighbourSearch* createKDTreeTreeHeap(const Matrix& cloud, const Index dim = std::numeric_limits<Index>::max(), const unsigned creationOptionFlags = 0, const Parameters& additionalParameters = Parameters());
00367         
00369         virtual ~NearestNeighbourSearch() {}
00370         
00371     protected:
00373         NearestNeighbourSearch(const Matrix& cloud, const Index dim, const unsigned creationOptionFlags);
00374         
00376 
00381         void checkSizesKnn(const Matrix& query, const IndexMatrix& indices, const Matrix& dists2, const Index k, const Vector* maxRadii = 0) const;
00382     };
00383     
00384     // Convenience typedefs
00385     
00387     typedef NearestNeighbourSearch<float> NNSearchF;
00389     typedef NearestNeighbourSearch<double> NNSearchD;
00390     
00392 }
00393 
00394 #endif // __NABO_H


libnabo
Author(s): Stéphane Magnenat
autogenerated on Thu Jan 2 2014 11:15:54