00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #include "nabo.h"
00033 #include "nabo_private.h"
00034 #include "index_heap.h"
00035 #include <limits>
00036 #include <algorithm>
00037 #include <stdexcept>
00038 #include <sstream>
00039
00045 namespace Nabo
00046 {
00047 using namespace std;
00048
00049
00050 struct runtime_error : std::runtime_error {
00051 stringstream ss;
00052
00053 template<typename T> runtime_error& operator<<(const T& t) {
00054 ss << t;
00055
00056
00057
00058 static_cast<std::runtime_error&>(*this) = std::runtime_error(ss.str());
00059
00060 return *this;
00061 }
00062
00063 runtime_error(): std::runtime_error("") {}
00064 runtime_error(const runtime_error& re): std::runtime_error(re.ss.str()), ss(re.ss.str()) {}
00065 virtual ~runtime_error() throw () {}
00066 };
00067
00068 template<typename T, typename CloudType>
00069 NearestNeighbourSearch<T, CloudType>::NearestNeighbourSearch(const CloudType& cloud, const Index dim, const unsigned creationOptionFlags):
00070 cloud(cloud),
00071 dim(min(dim, int(cloud.rows()))),
00072 creationOptionFlags(creationOptionFlags),
00073 minBound(Vector::Constant(this->dim, numeric_limits<T>::max())),
00074 maxBound(Vector::Constant(this->dim, numeric_limits<T>::min()))
00075 {
00076 if (cloud.cols() == 0)
00077 throw runtime_error() << "Cloud has no points";
00078 if (cloud.rows() == 0)
00079 throw runtime_error() << "Cloud has 0 dimensions";
00080 }
00081
00082 template<typename T, typename CloudType>
00083 unsigned long NearestNeighbourSearch<T, CloudType>::knn(const Vector& query, IndexVector& indices, Vector& dists2, const Index k, const T epsilon, const unsigned optionFlags, const T maxRadius) const
00084 {
00085 #ifdef EIGEN3_API
00086 const Eigen::Map<const Matrix> queryMatrix(&query.coeff(0,0), dim, 1);
00087 #else // EIGEN3_API
00088 const Eigen::Map<Matrix> queryMatrix(&query.coeff(0,0), dim, 1);
00089 #endif // EIGEN3_API
00090
00091
00092
00093
00094 IndexMatrix indexMatrix(k, 1);
00095 Matrix dists2Matrix(k, 1);
00096 const unsigned long stats = knn(queryMatrix, indexMatrix, dists2Matrix, k, epsilon, optionFlags, maxRadius);
00097 indices = indexMatrix.col(0);
00098 dists2 = dists2Matrix.col(0);
00099 return stats;
00100 }
00101
00102 template<typename T, typename CloudType>
00103 void NearestNeighbourSearch<T, CloudType>::checkSizesKnn(const Matrix& query, const IndexMatrix& indices, const Matrix& dists2, const Index k, const unsigned optionFlags, const Vector* maxRadii) const
00104 {
00105 const bool allowSelfMatch(optionFlags & NearestNeighbourSearch<T, CloudType>::ALLOW_SELF_MATCH);
00106 if (allowSelfMatch)
00107 {
00108 if (k > cloud.cols())
00109 throw runtime_error() << "Requesting more points (" << k << ") than available in cloud (" << cloud.cols() << ")";
00110 }
00111 else
00112 {
00113 if (k > cloud.cols()-1)
00114 throw runtime_error() << "Requesting more points (" << k << ") than available in cloud minus 1 (" << cloud.cols()-1 << ") (as self match is forbidden)";
00115 }
00116 if (query.rows() < dim)
00117 throw runtime_error() << "Query has less dimensions (" << query.rows() << ") than requested for cloud (" << dim << ")";
00118 if (indices.rows() != k)
00119 throw runtime_error() << "Index matrix has a different number of rows (" << indices.rows() << ") than k (" << k << ")";
00120 if (indices.cols() != query.cols())
00121 throw runtime_error() << "Index matrix has a different number of columns (" << indices.rows() << ") than query (" << query.cols() << ")";
00122 if (dists2.rows() != k)
00123 throw runtime_error() << "Distance matrix has a different number of rows (" << dists2.rows() << ") than k (" << k << ")";
00124 if (dists2.cols() != query.cols())
00125 throw runtime_error() << "Distance matrix has a different number of columns (" << dists2.rows() << ") than query (" << query.cols() << ")";
00126 if (maxRadii && (maxRadii->size() != query.cols()))
00127 throw runtime_error() << "Maximum radii vector has not the same length (" << maxRadii->size() << ") than query has columns (" << k << ")";
00128 const unsigned maxOptionFlagsValue(ALLOW_SELF_MATCH|SORT_RESULTS);
00129 if (optionFlags > maxOptionFlagsValue)
00130 throw runtime_error() << "OR-ed value of option flags (" << optionFlags << ") is larger than maximal valid value (" << maxOptionFlagsValue << ")";
00131 }
00132
00133
00134 template<typename T, typename CloudType>
00135 NearestNeighbourSearch<T, CloudType>* NearestNeighbourSearch<T, CloudType>::create(const CloudType& cloud, const Index dim, const SearchType preferedType, const unsigned creationOptionFlags, const Parameters& additionalParameters)
00136 {
00137 if (dim <= 0)
00138 throw runtime_error() << "Your space must have at least one dimension";
00139 switch (preferedType)
00140 {
00141 case BRUTE_FORCE: return new BruteForceSearch<T, CloudType>(cloud, dim, creationOptionFlags);
00142 case KDTREE_LINEAR_HEAP: return new KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt<T, IndexHeapBruteForceVector<Index,T>, CloudType>(cloud, dim, creationOptionFlags, additionalParameters);
00143 case KDTREE_TREE_HEAP: return new KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt<T, IndexHeapSTL<Index,T>, CloudType>(cloud, dim, creationOptionFlags, additionalParameters);
00144 #ifdef HAVE_OPENCL
00145 case KDTREE_CL_PT_IN_NODES: return new KDTreeBalancedPtInNodesStackOpenCL<T, CloudType>(cloud, dim, creationOptionFlags, CL_DEVICE_TYPE_GPU);
00146 case KDTREE_CL_PT_IN_LEAVES: return new KDTreeBalancedPtInLeavesStackOpenCL<T, CloudType>(cloud, dim, creationOptionFlags, CL_DEVICE_TYPE_GPU);
00147 case BRUTE_FORCE_CL: return new BruteForceSearchOpenCL<T, CloudType>(cloud, dim, creationOptionFlags, CL_DEVICE_TYPE_GPU);
00148 #else // HAVE_OPENCL
00149 case KDTREE_CL_PT_IN_NODES: throw runtime_error() << "OpenCL not found during compilation";
00150 case KDTREE_CL_PT_IN_LEAVES: throw runtime_error() << "OpenCL not found during compilation";
00151 case BRUTE_FORCE_CL: throw runtime_error() << "OpenCL not found during compilation";
00152 #endif // HAVE_OPENCL
00153 default: throw runtime_error() << "Unknown search type";
00154 }
00155 }
00156
00157 template<typename T, typename CloudType>
00158 NearestNeighbourSearch<T, CloudType>* NearestNeighbourSearch<T, CloudType>::createBruteForce(const CloudType& cloud, const Index dim, const unsigned creationOptionFlags)
00159 {
00160 if (dim <= 0)
00161 throw runtime_error() << "Your space must have at least one dimension";
00162 return new BruteForceSearch<T, CloudType>(cloud, dim, creationOptionFlags);
00163 }
00164
00165 template<typename T, typename CloudType>
00166 NearestNeighbourSearch<T, CloudType>* NearestNeighbourSearch<T, CloudType>::createKDTreeLinearHeap(const CloudType& cloud, const Index dim, const unsigned creationOptionFlags, const Parameters& additionalParameters)
00167 {
00168 if (dim <= 0)
00169 throw runtime_error() << "Your space must have at least one dimension";
00170 return new KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt<T, IndexHeapBruteForceVector<Index,T>, CloudType>(cloud, dim, creationOptionFlags, additionalParameters);
00171 }
00172
00173 template<typename T, typename CloudType>
00174 NearestNeighbourSearch<T, CloudType>* NearestNeighbourSearch<T, CloudType>::createKDTreeTreeHeap(const CloudType& cloud, const Index dim, const unsigned creationOptionFlags, const Parameters& additionalParameters)
00175 {
00176 if (dim <= 0)
00177 throw runtime_error() << "Your space must have at least one dimension";
00178 return new KDTreeUnbalancedPtInLeavesImplicitBoundsStackOpt<T, IndexHeapSTL<Index,T>, CloudType>(cloud, dim, creationOptionFlags, additionalParameters);
00179 }
00180
00181 template struct NearestNeighbourSearch<float>;
00182 template struct NearestNeighbourSearch<double>;
00183 template struct NearestNeighbourSearch<float, Eigen::Matrix3Xf>;
00184 template struct NearestNeighbourSearch<double, Eigen::Matrix3Xd>;
00185 template struct NearestNeighbourSearch<float, Eigen::Map<const Eigen::Matrix3Xf, Eigen::Aligned> >;
00186 template struct NearestNeighbourSearch<double, Eigen::Map<const Eigen::Matrix3Xd, Eigen::Aligned> >;
00187 }