kdtree_cpu.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 #include "nabo_experimental.h"
00033 #include "../nabo/index_heap.h"
00034 #include <iostream>
00035 #include <stdexcept>
00036 #include <limits>
00037 #include <queue>
00038 #include <algorithm>
00039 
00040 namespace Nabo
00041 {
00042         using namespace std;
00043         
00044         template<typename T, typename CloudType>
00045         size_t argMax(const typename NearestNeighbourSearch<T, CloudType>::Vector& v)
00046         {
00047                 T maxVal(0);
00048                 size_t maxIdx(0);
00049                 for (int i = 0; i < v.size(); ++i)
00050                 {
00051                         if (v[i] > maxVal)
00052                         {
00053                                 maxVal = v[i];
00054                                 maxIdx = i;
00055                         }
00056                 }
00057                 return maxIdx;
00058         }
00059 
00060         template<typename T, typename CloudType>
00061         size_t KDTreeBalancedPtInNodes<T, CloudType>::getTreeSize(size_t elCount) const
00062         {
00063                 // FIXME: 64 bits safe stuff, only work for 2^32 elements right now
00064                 size_t count = 0;
00065                 int i = 31;
00066                 for (; i >= 0; --i)
00067                 {
00068                         if (elCount & (1 << i))
00069                                 break;
00070                 }
00071                 for (int j = 0; j <= i; ++j)
00072                         count |= (1 << j);
00073                 //cerr << "tree size " << count << " (" << elCount << " elements)\n";
00074                 return count;
00075         }
00076         
00077         template<typename T, typename CloudType>
00078         typename KDTreeBalancedPtInNodes<T, CloudType>::IndexVector KDTreeBalancedPtInNodes<T, CloudType>::cloudIndexesFromNodesIndexes(const IndexVector& indexes) const
00079         {
00080                 IndexVector cloudIndexes(indexes.size());
00081                 for (int i = 0; i < indexes.size(); ++i)
00082                         cloudIndexes.coeffRef(i) = nodes[indexes[i]].index;
00083                 return cloudIndexes;
00084         }
00085 
00086         template<typename T, typename CloudType>
00087         void KDTreeBalancedPtInNodes<T, CloudType>::buildNodes(const BuildPointsIt first, const BuildPointsIt last, const size_t pos)
00088         {
00089                 const size_t count(last - first);
00090                 //cerr << count << endl;
00091                 if (count == 1)
00092                 {
00093                         nodes[pos] = Node(first->pos, -1, first->index);
00094                         return;
00095                 }
00096                 
00097                 // estimate variance
00098                 // get mean
00099                 Vector mean(Vector::Zero(this->dim));
00100                 for (BuildPointsCstIt it(first); it != last; ++it)
00101                         mean += it->pos;
00102                 mean /= last - first;
00103                 // get sum of variance
00104                 Vector var(Vector::Zero(this->dim));
00105                 for (BuildPointsCstIt it(first); it != last; ++it)
00106                         var += (it->pos - mean).cwise() * (it->pos - mean);
00107                 // get dimension of maxmial variance
00108                 const size_t cutDim = argMax<T>(var);
00109                 
00110                 // sort
00111                 sort(first, last, CompareDim(cutDim));
00112                 
00113                 // set node
00114                 const size_t recurseCount(count-1);
00115                 const size_t rightCount(recurseCount/2);
00116                 const size_t leftCount(recurseCount-rightCount);
00117                 assert(last - rightCount == first + leftCount + 1);
00118                 
00119                 nodes[pos] = Node((first+leftCount)->pos, cutDim, (first+leftCount)->index);
00120                 
00121                 //cerr << pos << " cutting on " << cutDim << " at " << (first+leftCount)->pos[cutDim] << endl;
00122                 
00123                 // recurse
00124                 if (count > 2)
00125                 {
00126                         buildNodes(first, first + leftCount, childLeft(pos));
00127                         buildNodes(first + leftCount + 1, last, childRight(pos));
00128                 }
00129                 else
00130                 {
00131                         nodes[childLeft(pos)] = Node(first->pos, -1, first->index);
00132                         nodes[childRight(pos)] = Node(Vector(), -2, 0);
00133                 }
00134         }
00135 
00136         template<typename T, typename CloudType>
00137         void KDTreeBalancedPtInNodes<T, CloudType>::dump(const Vector minValues, const Vector maxValues, const size_t pos) const
00138         {
00139                 const Node& node(nodes[pos]);
00140                 
00141                 if (node.dim >= -1)
00142                 {
00143                         if (this->dim == 2)
00144                                 cout << "<circle cx=\"" << 100*node.pos(0) << "\" cy=\"" << 100*node.pos(1) << "\" r=\"1\" stroke=\"black\" stroke-width=\"0.2\" fill=\"red\"/>" << endl;
00145                         else
00146                                 cout << "pt at\n" << node.pos << endl;
00147                 }
00148                 if (node.dim >= 0)
00149                 {
00150                         //cerr << "in bounds:\n" << minValues << "\nto\n" << maxValues << endl;
00151                         
00152                         // update bounds for left
00153                         Vector leftMaxValues(maxValues);
00154                         leftMaxValues[node.dim] = node.pos[node.dim];
00155                         // update bounds for right
00156                         Vector rightMinValues(minValues);
00157                         rightMinValues[node.dim] = node.pos[node.dim];
00158                         
00159                         // print line
00160                         if (this->dim == 2)
00161                                 cout << "<line x1=\"" << 100*rightMinValues(0) << "\" y1=\"" << 100*rightMinValues(1) << "\" x2=\"" << 100*leftMaxValues(0) << "\" y2=\"" << 100*leftMaxValues(1) << "\" style=\"stroke:rgb(0,0,0);stroke-width:0.2\"/>" << endl;
00162                         else
00163                                 cout << "cut from\n" << rightMinValues << "\nto\n" << leftMaxValues << endl;
00164                         // recurs
00165                         dump(minValues, leftMaxValues, childLeft(pos));
00166                         dump(rightMinValues, maxValues, childRight(pos));
00167                 }
00168         }
00169 
00170         template<typename T, typename CloudType>
00171         KDTreeBalancedPtInNodes<T, CloudType>::KDTreeBalancedPtInNodes(const CloudType& cloud):
00172                 NearestNeighbourSearch<T, CloudType>::NearestNeighbourSearch(cloud)
00173         {
00174                 // build point vector and compute bounds
00175                 BuildPoints buildPoints;
00176                 buildPoints.reserve(cloud.cols());
00177                 for (int i = 0; i < cloud.cols(); ++i)
00178                 {
00179                         const Vector& v(cloud.col(i));
00180                         buildPoints.push_back(BuildPoint(v, i));
00181                         const_cast<Vector&>(this->minBound) = this->minBound.cwise().min(v);
00182                         const_cast<Vector&>(this->maxBound) = this->maxBound.cwise().max(v);
00183                 }
00184                 
00185                 // create nodes
00186                 nodes.resize(getTreeSize(cloud.cols()));
00187                 buildNodes(buildPoints.begin(), buildPoints.end(), 0);
00188                 
00189                 // dump nodes
00190                 //dump(minBound, maxBound, 0);
00191         }
00192         
00193         // points in nodes, priority queue
00194         
00195         template<typename T, typename CloudType>
00196         KDTreeBalancedPtInNodesPQ<T, CloudType>::KDTreeBalancedPtInNodesPQ(const CloudType& cloud):
00197                 KDTreeBalancedPtInNodes<T, CloudType>::KDTreeBalancedPtInNodes(cloud)
00198         {
00199         }
00200 
00201         template<typename T, typename CloudType>
00202         typename KDTreeBalancedPtInNodesPQ<T, CloudType>::IndexVector KDTreeBalancedPtInNodesPQ<T, CloudType>::knn(const Vector& query, const Index k, const T epsilon, const unsigned optionFlags)
00203         {
00204                 typedef priority_queue<SearchElement> Queue;
00205                 
00206                 const T maxError(1 + epsilon);
00207                 const bool allowSelfMatch(optionFlags & NearestNeighbourSearch<T>::ALLOW_SELF_MATCH);
00208                 
00209                 Queue queue;
00210                 queue.push(SearchElement(0, 0));
00211                 IndexHeapSTL<Index, T> heap(k);
00212                 statistics.lastQueryVisitCount = 0;
00213                 
00214                 while (!queue.empty())
00215                 {
00216                         SearchElement el(queue.top());
00217                         queue.pop();
00218                         
00219                         // nothing is closer, we found best
00220                         if (el.minDist * maxError > heap.headValue())
00221                                 break;
00222                         
00223                         size_t n(el.index);
00224                         while (1)
00225                         {
00226                                 const Node& node(nodes[n]);
00227                                 assert (node.dim != -2);
00228                                 
00229                                 // TODO: optimise dist while going down
00230                                 const T dist(dist2<T>(node.pos, query));
00231                                 if ((dist < heap.headValue()) &&
00232                                         (allowSelfMatch || (dist > numeric_limits<T>::epsilon())))
00233                                         heap.replaceHead(n, dist);
00234                                 
00235                                 // if we are at leaf, stop
00236                                 if (node.dim < 0)
00237                                         break;
00238                                 
00239                                 const T offset(query.coeff(node.dim) - node.pos.coeff(node.dim));
00240                                 const T offset2(offset * offset);
00241                                 const T bestDist(heap.headValue());
00242                                 if (offset > 0)
00243                                 {
00244                                         // enqueue offside ?
00245                                         if (offset2 < bestDist && nodes[childLeft(n)].dim != -2)
00246                                                 queue.push(SearchElement(childLeft(n), offset2));
00247                                         // continue onside
00248                                         if (nodes[childRight(n)].dim != -2)
00249                                                 n = childRight(n);
00250                                         else
00251                                                 break;
00252                                 }
00253                                 else
00254                                 {
00255                                         // enqueue offside ?
00256                                         if (offset2 < bestDist && nodes[childRight(n)].dim != -2)
00257                                                 queue.push(SearchElement(childRight(n), offset2));
00258                                         // continue onside
00259                                         if (nodes[childLeft(n)].dim != -2)
00260                                                 n = childLeft(n);
00261                                         else
00262                                                 break;
00263                                 }
00264                                 ++statistics.lastQueryVisitCount;
00265                         }
00266                 }
00267                 statistics.totalVisitCount += statistics.lastQueryVisitCount;
00268                 
00269                 if (optionFlags & NearestNeighbourSearch<T>::SORT_RESULTS)
00270                         heap.sort();
00271                 
00272                 return cloudIndexesFromNodesIndexes(heap.getIndexes());
00273         }
00274 
00275         template struct KDTreeBalancedPtInNodesPQ<float>;
00276         template struct KDTreeBalancedPtInNodesPQ<double>;
00277         template struct KDTreeBalancedPtInNodesPQ<float, Eigen::Matrix3Xf>;
00278         template struct KDTreeBalancedPtInNodesPQ<double, Eigen::Matrix3Xd>;
00279         template struct KDTreeBalancedPtInNodesPQ<float, Eigen::Map<const Eigen::Matrix3Xf, Eigen::Aligned> >;
00280         template struct KDTreeBalancedPtInNodesPQ<double, Eigen::Map<const Eigen::Matrix3Xd, Eigen::Aligned> >;
00281         
00282         // points in nodes, stack
00283         
00284         template<typename T, typename CloudType>
00285         KDTreeBalancedPtInNodesStack<T, CloudType>::KDTreeBalancedPtInNodesStack(const CloudType& cloud):
00286                 KDTreeBalancedPtInNodes<T, CloudType>::KDTreeBalancedPtInNodes(cloud)
00287         {
00288         }
00289         
00290         template<typename T, typename CloudType>
00291         typename KDTreeBalancedPtInNodesStack<T, CloudType>::IndexVector KDTreeBalancedPtInNodesStack<T, CloudType>::knn(const Vector& query, const Index k, const T epsilon, const unsigned optionFlags)
00292         {
00293                 const bool allowSelfMatch(optionFlags & NearestNeighbourSearch<T>::ALLOW_SELF_MATCH);
00294                 
00295                 assert(nodes.size() > 0);
00296                 assert(nodes[0].pos.size() == query.size());
00297                 Heap heap(k);
00298                 Vector off(Vector::Zero(nodes[0].pos.size()));
00299                 
00300                 statistics.lastQueryVisitCount = 0;
00301                 
00302                 recurseKnn(query, 0, 0, heap, off, 1 + epsilon, allowSelfMatch);
00303                 
00304                 if (optionFlags & NearestNeighbourSearch<T>::SORT_RESULTS)
00305                         heap.sort();
00306                 
00307                 statistics.totalVisitCount += statistics.lastQueryVisitCount;
00308                 
00309                 return cloudIndexesFromNodesIndexes(heap.getIndexes());
00310         }
00311         
00312         template<typename T, typename CloudType>
00313         void KDTreeBalancedPtInNodesStack<T, CloudType>::recurseKnn(const Vector& query, const size_t n, T rd, Heap& heap, Vector& off, const T maxError, const bool allowSelfMatch)
00314         {
00315                 const Node& node(nodes[n]);
00316                 const int cd(node.dim);
00317                 
00318                 ++statistics.lastQueryVisitCount;
00319                 
00320                 if (cd == -2)
00321                         return;
00322                 
00323                 const T dist(dist2<T, CloudType>(node.pos, query));
00324                 if ((dist < heap.headValue()) &&
00325                         (allowSelfMatch || (dist > numeric_limits<T>::epsilon()))
00326                 )
00327                         heap.replaceHead(n, dist);
00328                 
00329                 if (cd != -1)
00330                 {
00331                         const T old_off(off.coeff(cd));
00332                         const T new_off(query.coeff(cd) - node.pos.coeff(cd));
00333                         if (new_off > 0)
00334                         {
00335                                 recurseKnn(query, childRight(n), rd, heap, off, maxError, allowSelfMatch);
00336                                 rd += - old_off*old_off + new_off*new_off;
00337                                 if (rd * maxError < heap.headValue())
00338                                 {
00339                                         off.coeffRef(cd) = new_off;
00340                                         recurseKnn(query, childLeft(n), rd, heap, off, maxError, allowSelfMatch);
00341                                         off.coeffRef(cd) = old_off;
00342                                 }
00343                         }
00344                         else
00345                         {
00346                                 recurseKnn(query, childLeft(n), rd, heap, off, maxError, allowSelfMatch);
00347                                 rd += - old_off*old_off + new_off*new_off;
00348                                 if (rd * maxError < heap.headValue())
00349                                 {
00350                                         off.coeffRef(cd) = new_off;
00351                                         recurseKnn(query, childRight(n), rd, heap, off, maxError, allowSelfMatch);
00352                                         off.coeffRef(cd) = old_off;
00353                                 }
00354                         }
00355                 }
00356         }
00357         
00358         template struct KDTreeBalancedPtInNodesStack<float>;
00359         template struct KDTreeBalancedPtInNodesStack<double>;
00360         template struct KDTreeBalancedPtInNodesStack<float, Eigen::Matrix3Xf>;
00361         template struct KDTreeBalancedPtInNodesStack<double, Eigen::Matrix3Xd>;
00362         template struct KDTreeBalancedPtInNodesStack<float, Eigen::Map<const Eigen::Matrix3Xf, Eigen::Aligned> >;
00363         template struct KDTreeBalancedPtInNodesStack<double, Eigen::Map<const Eigen::Matrix3Xd, Eigen::Aligned> >;
00364         
00365         // NEW:
00366         
00367         template<typename T, typename CloudType>
00368         size_t KDTreeBalancedPtInLeavesStack<T, CloudType>::getTreeSize(size_t elCount) const
00369         {
00370                 // FIXME: 64 bits safe stuff, only work for 2^32 elements right now
00371                 assert(elCount > 0);
00372                 elCount --;
00373                 size_t count = 0;
00374                 int i = 31;
00375                 for (; i >= 0; --i)
00376                 {
00377                         if (elCount & (1 << i))
00378                                 break;
00379                 }
00380                 for (int j = 0; j <= i; ++j)
00381                         count |= (1 << j);
00382                 count <<= 1;
00383                 count |= 1;
00384                 return count;
00385         }
00386         
00387         template<typename T, typename CloudType>
00388         void KDTreeBalancedPtInLeavesStack<T, CloudType>::buildNodes(const BuildPointsIt first, const BuildPointsIt last, const size_t pos, const Vector minValues, const Vector maxValues, const bool balanceVariance)
00389         {
00390                 const size_t count(last - first);
00391                 //cerr << count << endl;
00392                 if (count == 1)
00393                 {
00394                         const int dim = -2-(first->index);
00395                         assert(pos < nodes.size());
00396                         nodes[pos] = Node(dim);
00397                         return;
00398                 }
00399                 
00400                 size_t cutDim;
00401                 if (balanceVariance)
00402                 {
00403                         // estimate variance
00404                         // get mean
00405                         Vector mean(Vector::Zero(this->dim));
00406                         for (BuildPointsCstIt it(first); it != last; ++it)
00407                                 mean += it->pos;
00408                         mean /= last - first;
00409                         // get sum of variance
00410                         Vector var(Vector::Zero(this->dim));
00411                         for (BuildPointsCstIt it(first); it != last; ++it)
00412                                 var += (it->pos - mean).cwise() * (it->pos - mean);
00413                         // get dimension of maxmial variance
00414                         cutDim = argMax<T>(var);
00415                 }
00416                 else
00417                 {
00418                         // find the largest dimension of the box
00419                         cutDim = argMax<T>(maxValues - minValues);
00420                 }
00421                 
00422                 // compute number of elements
00423                 const size_t rightCount(count/2);
00424                 const size_t leftCount(count - rightCount);
00425                 assert(last - rightCount == first + leftCount);
00426                 
00427                 // sort
00428                 //sort(first, last, CompareDim(cutDim));
00429                 nth_element(first, first + leftCount, last, CompareDim(cutDim));
00430                 
00431                 // set node
00432                 const T cutVal((first+leftCount)->pos.coeff(cutDim));
00433                 nodes[pos] = Node(cutDim, cutVal);
00434                 
00435                 //cerr << pos << " cutting on " << cutDim << " at " << (first+leftCount)->pos[cutDim] << endl;
00436                 
00437                 // update bounds for left
00438                 Vector leftMaxValues(maxValues);
00439                 leftMaxValues[cutDim] = cutVal;
00440                 // update bounds for right
00441                 Vector rightMinValues(minValues);
00442                 rightMinValues[cutDim] = cutVal;
00443                 
00444                 // recurse
00445                 buildNodes(first, first + leftCount, childLeft(pos), minValues, leftMaxValues, balanceVariance);
00446                 buildNodes(first + leftCount, last, childRight(pos), rightMinValues, maxValues, balanceVariance);
00447         }
00448 
00449         template<typename T, typename CloudType>
00450         KDTreeBalancedPtInLeavesStack<T, CloudType>::KDTreeBalancedPtInLeavesStack(const CloudType& cloud, const bool balanceVariance):
00451                 NearestNeighbourSearch<T, CloudType>::NearestNeighbourSearch(cloud)
00452         {
00453                 // build point vector and compute bounds
00454                 BuildPoints buildPoints;
00455                 buildPoints.reserve(cloud.cols());
00456                 for (int i = 0; i < cloud.cols(); ++i)
00457                 {
00458                         const Vector& v(cloud.col(i));
00459                         buildPoints.push_back(BuildPoint(v, i));
00460                         const_cast<Vector&>(minBound) = minBound.cwise().min(v);
00461                         const_cast<Vector&>(maxBound) = maxBound.cwise().max(v);
00462                 }
00463                 
00464                 // create nodes
00465                 nodes.resize(getTreeSize(cloud.cols()));
00466                 buildNodes(buildPoints.begin(), buildPoints.end(), 0, minBound, maxBound, balanceVariance);
00467                 //for (size_t i = 0; i < nodes.size(); ++i)
00468                 //      cout << i << ": " << nodes[i].dim << " " << nodes[i].cutVal << endl;
00469         }
00470         
00471         template<typename T, typename CloudType>
00472         typename KDTreeBalancedPtInLeavesStack<T, CloudType>::IndexVector KDTreeBalancedPtInLeavesStack<T, CloudType>::knn(const Vector& query, const Index k, const T epsilon, const unsigned optionFlags)
00473         {
00474                 const bool allowSelfMatch(optionFlags & NearestNeighbourSearch<T, CloudType>::ALLOW_SELF_MATCH);
00475                 
00476                 assert(nodes.size() > 0);
00477                 Heap heap(k);
00478                 Vector off(Vector::Zero(query.size()));
00479                 
00480                 statistics.lastQueryVisitCount = 0;
00481                 
00482                 recurseKnn(query, 0, 0, heap, off, 1 + epsilon, allowSelfMatch);
00483                 
00484                 if (optionFlags & NearestNeighbourSearch<T>::SORT_RESULTS)
00485                         heap.sort();
00486                 
00487                 statistics.totalVisitCount += statistics.lastQueryVisitCount;
00488                 
00489                 return heap.getIndexes();
00490         }
00491         
00492         template<typename T, typename CloudType>
00493         void KDTreeBalancedPtInLeavesStack<T, CloudType>::recurseKnn(const Vector& query, const size_t n, T rd, Heap& heap, Vector& off, const T maxError, const bool allowSelfMatch)
00494         {
00495                 const Node& node(nodes[n]);
00496                 const int cd(node.dim);
00497                 
00498                 ++statistics.lastQueryVisitCount;
00499                 
00500                 if (cd < 0)
00501                 {
00502                         if (cd == -1)
00503                                 return;
00504                         const int index(-(cd + 2));
00505                         const T dist(dist2<T>(query, cloud.col(index)));
00506                         if ((dist < heap.headValue()) &&
00507                                 (allowSelfMatch || (dist > numeric_limits<T>::epsilon()))
00508                         )
00509                                 heap.replaceHead(index, dist);
00510                 }
00511                 else
00512                 {
00513                         const T old_off(off.coeff(cd));
00514                         const T new_off(query.coeff(cd) - node.cutVal);
00515                         if (new_off > 0)
00516                         {
00517                                 recurseKnn(query, childRight(n), rd, heap, off, maxError, allowSelfMatch);
00518                                 rd += - old_off*old_off + new_off*new_off;
00519                                 if (rd * maxError < heap.headValue())
00520                                 {
00521                                         off.coeffRef(cd) = new_off;
00522                                         recurseKnn(query, childLeft(n), rd, heap, off, maxError, allowSelfMatch);
00523                                         off.coeffRef(cd) = old_off;
00524                                 }
00525                         }
00526                         else
00527                         {
00528                                 recurseKnn(query, childLeft(n), rd, heap, off, maxError, allowSelfMatch);
00529                                 rd += - old_off*old_off + new_off*new_off;
00530                                 if (rd * maxError < heap.headValue())
00531                                 {
00532                                         off.coeffRef(cd) = new_off;
00533                                         recurseKnn(query, childRight(n), rd, heap, off, maxError, allowSelfMatch);
00534                                         off.coeffRef(cd) = old_off;
00535                                 }
00536                         }
00537                 }
00538         }
00539         
00540         template struct KDTreeBalancedPtInLeavesStack<float>;
00541         template struct KDTreeBalancedPtInLeavesStack<double>;
00542         template struct KDTreeBalancedPtInLeavesStack<float, Eigen::Matrix3Xf>;
00543         template struct KDTreeBalancedPtInLeavesStack<double, Eigen::Matrix3Xd>;
00544         template struct KDTreeBalancedPtInLeavesStack<float, Eigen::Map<const Eigen::Matrix3Xf, Eigen::Aligned> >;
00545         template struct KDTreeBalancedPtInLeavesStack<double, Eigen::Map<const Eigen::Matrix3Xd, Eigen::Aligned> >;
00546         
00547         
00548         
00549         template<typename T, typename Heap, typename CloudType>
00550         unsigned KDTreeUnbalancedPtInLeavesImplicitBoundsStack<T, Heap, CloudType>::buildNodes(const BuildPointsIt first, const BuildPointsIt last, const Vector minValues, const Vector maxValues)
00551         {
00552                 const size_t count(last - first);
00553                 const unsigned pos(nodes.size());
00554                 
00555                 //cerr << count << endl;
00556                 if (count == 1)
00557                 {
00558                         nodes.push_back(Node(first->index));
00559                         return pos;
00560                 }
00561                 
00562                 // find the largest dimension of the box
00563                 const unsigned cutDim = argMax<T>(maxValues - minValues);
00564                 T cutVal((maxValues(cutDim) + minValues(cutDim))/2);
00565                 
00566                 // TODO: do only sort once
00567                 // sort
00568                 sort(first, last, CompareDim(cutDim));
00569                 
00570                 // TODO: optimise using binary search
00571                 size_t rightStart(0);
00572                 while (rightStart < count && (first+rightStart)->pos.coeff(cutDim) < cutVal)
00573                         ++rightStart;
00574                 
00575                 // prevent trivial splits
00576                 if (rightStart == 0)
00577                 {
00578                         cutVal = first->pos.coeff(cutDim);
00579                         rightStart = 1;
00580                 }
00581                 else if (rightStart == count)
00582                 {
00583                         rightStart = count - 1;
00584                         cutVal = (first + rightStart)->pos.coeff(cutDim);
00585                 }
00586                 
00587                 // update bounds for left
00588                 Vector leftMaxValues(maxValues);
00589                 leftMaxValues[cutDim] = cutVal;
00590                 // update bounds for right
00591                 Vector rightMinValues(minValues);
00592                 rightMinValues[cutDim] = cutVal;
00593                 
00594                 // count for recursion
00595                 const size_t rightCount(count - rightStart);
00596                 const size_t leftCount(count - rightCount);
00597                 
00598                 // add this
00599                 nodes.push_back(Node(cutDim, cutVal, 0));
00600                 
00601                 // recurse
00602                 const unsigned __attribute__ ((unused)) leftChild = buildNodes(first, first + leftCount, minValues, leftMaxValues);
00603                 assert(leftChild == pos + 1);
00604                 const unsigned rightChild = buildNodes(first + leftCount, last, rightMinValues, maxValues);
00605                 
00606                 // write right child index and return
00607                 nodes[pos].rightChild = rightChild;
00608                 return pos;
00609         }
00610 
00611         template<typename T, typename Heap, typename CloudType>
00612         KDTreeUnbalancedPtInLeavesImplicitBoundsStack<T, Heap, CloudType>::KDTreeUnbalancedPtInLeavesImplicitBoundsStack(const CloudType& cloud):
00613                 NearestNeighbourSearch<T, CloudType>::NearestNeighbourSearch(cloud)
00614         {
00615                 // build point vector and compute bounds
00616                 BuildPoints buildPoints;
00617                 buildPoints.reserve(cloud.cols());
00618                 for (int i = 0; i < cloud.cols(); ++i)
00619                 {
00620                         const Vector& v(cloud.col(i));
00621                         buildPoints.push_back(BuildPoint(v, i));
00622                         const_cast<Vector&>(minBound) = minBound.cwise().min(v);
00623                         const_cast<Vector&>(maxBound) = maxBound.cwise().max(v);
00624                 }
00625                 
00626                 // create nodes
00627                 //nodes.resize(getTreeSize(cloud.cols()));
00628                 buildNodes(buildPoints.begin(), buildPoints.end(), minBound, maxBound);
00629                 //for (size_t i = 0; i < nodes.size(); ++i)
00630                 //      cout << i << ": " << nodes[i].dim << " " << nodes[i].cutVal <<  " " << nodes[i].rightChild << endl;
00631         }
00632         
00633         template<typename T, typename Heap, typename CloudType>
00634         typename KDTreeUnbalancedPtInLeavesImplicitBoundsStack<T, Heap, CloudType>::IndexVector KDTreeUnbalancedPtInLeavesImplicitBoundsStack<T, Heap, CloudType>::knn(const Vector& query, const Index k, const T epsilon, const unsigned optionFlags)
00635         {
00636                 const bool allowSelfMatch(optionFlags & NearestNeighbourSearch<T, CloudType>::ALLOW_SELF_MATCH);
00637                 
00638                 assert(nodes.size() > 0);
00639                 Heap heap(k);
00640                 Vector off(Vector::Zero(query.size()));
00641                 
00642                 statistics.lastQueryVisitCount = 0;
00643                 
00644                 recurseKnn(query, 0, 0, heap, off, 1+epsilon, allowSelfMatch);
00645                 
00646                 if (optionFlags & NearestNeighbourSearch<T, CloudType>::SORT_RESULTS)
00647                         heap.sort();
00648                 
00649                 statistics.totalVisitCount += statistics.lastQueryVisitCount;
00650                 
00651                 return heap.getIndexes();
00652         }
00653         
00654         template<typename T, typename Heap, typename CloudType>
00655         typename KDTreeUnbalancedPtInLeavesImplicitBoundsStack<T, Heap, CloudType>::IndexMatrix KDTreeUnbalancedPtInLeavesImplicitBoundsStack<T, Heap, CloudType>::knnM(const Matrix& query, const Index k, const T epsilon, const unsigned optionFlags)
00656         {
00657                 const bool allowSelfMatch(optionFlags & NearestNeighbourSearch<T, CloudType>::ALLOW_SELF_MATCH);
00658                 assert(nodes.size() > 0);
00659                 
00660                 assert(nodes.size() > 0);
00661                 Heap heap(k);
00662                 Vector off(query.rows());
00663                 
00664                 IndexMatrix result(k, query.cols());
00665                 const int colCount(query.cols());
00666                 
00667                 for (int i = 0; i < colCount; ++i)
00668                 {
00669                         const Vector& q(query.col(i));
00670                         
00671                         off.setZero();
00672                         heap.reset();
00673                         
00674                         statistics.lastQueryVisitCount = 0;
00675                         
00676                         recurseKnn(q, 0, 0, heap, off, 1+epsilon, allowSelfMatch);
00677                         
00678                         if (optionFlags & NearestNeighbourSearch<T>::SORT_RESULTS)
00679                                 heap.sort();
00680                         
00681                         result.col(i) = heap.getIndexes();
00682                         
00683                         statistics.totalVisitCount += statistics.lastQueryVisitCount;
00684                 }
00685                 
00686                 return result;
00687         }
00688         
00689         template<typename T, typename Heap, typename CloudType>
00690         void KDTreeUnbalancedPtInLeavesImplicitBoundsStack<T, Heap, CloudType>::recurseKnn(const Vector& query, const unsigned n, T rd, Heap& heap, Vector& off, const T maxError, const bool allowSelfMatch)
00691         {
00692                 const Node& node(nodes[n]);
00693                 //++statistics.lastQueryVisitCount;
00694                 
00695                 if (node.rightChild == Node::INVALID_CHILD)
00696                 {
00697                         const unsigned index(node.ptIndex);
00698                         //const T dist(dist2<T>(query, cloud.col(index)));
00699                         //const T dist((query - cloud.col(index)).squaredNorm());
00700                         T dist(0);
00701                         const T* qPtr(&query.coeff(0));
00702                         const T* dPtr(&cloud.coeff(0, index));
00703                         const int dim(query.size());
00704                         for (int i = 0; i < dim; ++i)
00705                         {
00706                                 const T diff(*qPtr - *dPtr);
00707                                 dist += diff*diff;
00708                                 qPtr++; dPtr++;
00709                         }
00710                         if ((dist < heap.headValue()) &&
00711                                 (allowSelfMatch || (dist > numeric_limits<T>::epsilon()))
00712                         )
00713                                 heap.replaceHead(index, dist);
00714                 }
00715                 else
00716                 {
00717                         const unsigned cd(node.dim);
00718                         const T old_off(off.coeff(cd));
00719                         const T new_off(query.coeff(cd) - node.cutVal);
00720                         if (new_off > 0)
00721                         {
00722                                 recurseKnn(query, node.rightChild, rd, heap, off, maxError, allowSelfMatch);
00723                                 rd += - old_off*old_off + new_off*new_off;
00724                                 if (rd * maxError < heap.headValue())
00725                                 {
00726                                         off.coeffRef(cd) = new_off;
00727                                         recurseKnn(query, n + 1, rd, heap, off, maxError, allowSelfMatch);
00728                                         off.coeffRef(cd) = old_off;
00729                                 }
00730                         }
00731                         else
00732                         {
00733                                 recurseKnn(query, n+1, rd, heap, off, maxError, allowSelfMatch);
00734                                 rd += - old_off*old_off + new_off*new_off;
00735                                 if (rd * maxError < heap.headValue())
00736                                 {
00737                                         off.coeffRef(cd) = new_off;
00738                                         recurseKnn(query, node.rightChild, rd, heap, off, maxError, allowSelfMatch);
00739                                         off.coeffRef(cd) = old_off;
00740                                 }
00741                         }
00742                 }
00743         }
00744         
00745         template struct KDTreeUnbalancedPtInLeavesImplicitBoundsStack<float,IndexHeapSTL<int,float>>;
00746         template struct KDTreeUnbalancedPtInLeavesImplicitBoundsStack<float,IndexHeapBruteForceVector<int,float>>;
00747         template struct KDTreeUnbalancedPtInLeavesImplicitBoundsStack<double,IndexHeapSTL<int,double>>;
00748         template struct KDTreeUnbalancedPtInLeavesImplicitBoundsStack<double,IndexHeapBruteForceVector<int,double>>;
00749 
00750         template struct KDTreeUnbalancedPtInLeavesImplicitBoundsStack<float,IndexHeapSTL<int,float>,Eigen::Matrix3Xf>;
00751         template struct KDTreeUnbalancedPtInLeavesImplicitBoundsStack<float,IndexHeapBruteForceVector<int,float>,Eigen::Matrix3Xf>;
00752         template struct KDTreeUnbalancedPtInLeavesImplicitBoundsStack<double,IndexHeapSTL<int,double>,Eigen::Matrix3Xd>;
00753         template struct KDTreeUnbalancedPtInLeavesImplicitBoundsStack<double,IndexHeapBruteForceVector<int,double>,Eigen::Matrix3Xd>;
00754 
00755         template struct KDTreeUnbalancedPtInLeavesImplicitBoundsStack<float,IndexHeapSTL<int,float>,Eigen::Map<const Eigen::Matrix3Xf, Eigen::Aligned> >;
00756         template struct KDTreeUnbalancedPtInLeavesImplicitBoundsStack<float,IndexHeapBruteForceVector<int,float>,Eigen::Map<const Eigen::Matrix3Xf, Eigen::Aligned> >;
00757         template struct KDTreeUnbalancedPtInLeavesImplicitBoundsStack<double,IndexHeapSTL<int,double>,Eigen::Map<const Eigen::Matrix3Xd, Eigen::Aligned> >;
00758         template struct KDTreeUnbalancedPtInLeavesImplicitBoundsStack<double,IndexHeapBruteForceVector<int,double>,Eigen::Map<const Eigen::Matrix3Xd, Eigen::Aligned> >;
00759         
00760         template<typename T, typename CloudType>
00761         unsigned KDTreeUnbalancedPtInLeavesExplicitBoundsStack<T, CloudType>::buildNodes(const BuildPointsIt first, const BuildPointsIt last, const Vector minValues, const Vector maxValues)
00762         {
00763                 const size_t count(last - first);
00764                 const unsigned pos(nodes.size());
00765                 
00766                 //cerr << count << endl;
00767                 if (count == 1)
00768                 {
00769                         const int dim = -1-(first->index);
00770                         nodes.push_back(Node(dim));
00771                         return pos;
00772                 }
00773                 
00774                 // find the largest dimension of the box
00775                 const int cutDim = argMax<T>(maxValues - minValues);
00776                 T cutVal((maxValues(cutDim) + minValues(cutDim))/2);
00777                 
00778                 // TODO: do only sort once
00779                 // sort
00780                 sort(first, last, CompareDim(cutDim));
00781                 
00782                 // TODO: optimise using binary search
00783                 size_t rightStart(0);
00784                 while (rightStart < count && (first+rightStart)->pos.coeff(cutDim) < cutVal)
00785                         ++rightStart;
00786                 
00787                 // prevent trivial splits
00788                 if (rightStart == 0)
00789                 {
00790                         cutVal = first->pos.coeff(cutDim);
00791                         rightStart = 1;
00792                 }
00793                 else if (rightStart == count)
00794                 {
00795                         rightStart = count - 1;
00796                         cutVal = (first + rightStart)->pos.coeff(cutDim);
00797                 }
00798                 
00799                 // update bounds for left
00800                 Vector leftMaxValues(maxValues);
00801                 leftMaxValues[cutDim] = cutVal;
00802                 // update bounds for right
00803                 Vector rightMinValues(minValues);
00804                 rightMinValues[cutDim] = cutVal;
00805                 
00806                 // count for recursion
00807                 const size_t rightCount(count - rightStart);
00808                 const size_t leftCount(count - rightCount);
00809                 
00810                 // add this
00811                 nodes.push_back(Node(cutDim, cutVal, minValues.coeff(cutDim), maxValues.coeff(cutDim)));
00812                 
00813                 // recurse
00814                 const unsigned __attribute__ ((unused)) leftChild = buildNodes(first, first + leftCount, minValues, leftMaxValues);
00815                 assert(leftChild == pos + 1);
00816                 const unsigned rightChild = buildNodes(first + leftCount, last, rightMinValues, maxValues);
00817                 
00818                 // write right child index and return
00819                 nodes[pos].rightChild = rightChild;
00820                 return pos;
00821         }
00822 
00823         template<typename T, typename CloudType>
00824         KDTreeUnbalancedPtInLeavesExplicitBoundsStack<T, CloudType>::KDTreeUnbalancedPtInLeavesExplicitBoundsStack(const CloudType& cloud):
00825                 NearestNeighbourSearch<T, CloudType>::NearestNeighbourSearch(cloud)
00826         {
00827                 // build point vector and compute bounds
00828                 BuildPoints buildPoints;
00829                 buildPoints.reserve(cloud.cols());
00830                 for (int i = 0; i < cloud.cols(); ++i)
00831                 {
00832                         const Vector& v(cloud.col(i));
00833                         buildPoints.push_back(BuildPoint(v, i));
00834                         const_cast<Vector&>(minBound) = minBound.cwise().min(v);
00835                         const_cast<Vector&>(maxBound) = maxBound.cwise().max(v);
00836                 }
00837                 
00838                 // create nodes
00839                 //nodes.resize(getTreeSize(cloud.cols()));
00840                 buildNodes(buildPoints.begin(), buildPoints.end(), minBound, maxBound);
00841                 //for (size_t i = 0; i < nodes.size(); ++i)
00842                 //      cout << i << ": " << nodes[i].dim << " " << nodes[i].cutVal <<  " " << nodes[i].rightChild << endl;
00843         }
00844         
00845         template<typename T, typename CloudType>
00846         typename KDTreeUnbalancedPtInLeavesExplicitBoundsStack<T, CloudType>::IndexVector KDTreeUnbalancedPtInLeavesExplicitBoundsStack<T, CloudType>::knn(const Vector& query, const Index k, const T epsilon, const unsigned optionFlags)
00847         {
00848                 const bool allowSelfMatch(optionFlags & NearestNeighbourSearch<T, CloudType>::ALLOW_SELF_MATCH);
00849                 
00850                 assert(nodes.size() > 0);
00851                 Heap heap(k);
00852                 
00853                 statistics.lastQueryVisitCount = 0;
00854                 
00855                 recurseKnn(query, 0, 0, heap, 1+epsilon, allowSelfMatch);
00856                 
00857                 if (optionFlags & NearestNeighbourSearch<T>::SORT_RESULTS)
00858                         heap.sort();
00859                 
00860                 statistics.totalVisitCount += statistics.lastQueryVisitCount;
00861                 
00862                 return heap.getIndexes();
00863         }
00864         
00865         template<typename T, typename CloudType>
00866         void KDTreeUnbalancedPtInLeavesExplicitBoundsStack<T, CloudType>::recurseKnn(const Vector& query, const size_t n, T rd, Heap& heap, const T maxError, const bool allowSelfMatch)
00867         {
00868                 const Node& node(nodes[n]);
00869                 const int cd(node.dim);
00870                 
00871                 ++statistics.lastQueryVisitCount;
00872                 
00873                 if (cd < 0)
00874                 {
00875                         const int index(-(cd + 1));
00876                         const T dist(dist2<T>(query, cloud.col(index)));
00877                         if ((dist < heap.headValue()) &&
00878                                 (allowSelfMatch || (dist > numeric_limits<T>::epsilon()))
00879                         )
00880                                 heap.replaceHead(index, dist);
00881                 }
00882                 else
00883                 {
00884                         const T q_val(query.coeff(cd));
00885                         const T cut_diff(q_val - node.cutVal);
00886                         if (cut_diff < 0)
00887                         {
00888                                 recurseKnn(query, n+1, rd, heap, maxError, allowSelfMatch);
00889                                 
00890                                 T box_diff = node.lowBound - q_val;
00891                                 if (box_diff < 0)
00892                                         box_diff = 0;
00893                                 
00894                                 rd += cut_diff*cut_diff - box_diff*box_diff;
00895                                 
00896                                 if (rd * maxError < heap.headValue())
00897                                         recurseKnn(query, node.rightChild, rd, heap, maxError, allowSelfMatch);
00898                         }
00899                         else
00900                         {
00901                                 recurseKnn(query, node.rightChild, rd, heap, maxError, allowSelfMatch);
00902                                 
00903                                 T box_diff = q_val - node.highBound;
00904                                 if (box_diff < 0)
00905                                         box_diff = 0;
00906                                 
00907                                 rd += cut_diff*cut_diff - box_diff*box_diff;
00908                                 
00909                                 if (rd * maxError < heap.headValue())
00910                                         recurseKnn(query, n + 1, rd, heap, maxError, allowSelfMatch);
00911                         }
00912                 }
00913         }
00914         
00915         template struct KDTreeUnbalancedPtInLeavesExplicitBoundsStack<float>;
00916         template struct KDTreeUnbalancedPtInLeavesExplicitBoundsStack<double>;
00917         template struct KDTreeUnbalancedPtInLeavesExplicitBoundsStack<float, Eigen::Matrix3Xf>;
00918         template struct KDTreeUnbalancedPtInLeavesExplicitBoundsStack<double, Eigen::Matrix3Xd>;
00919         template struct KDTreeUnbalancedPtInLeavesExplicitBoundsStack<float, Eigen::Map<const Eigen::Matrix3Xf, Eigen::Aligned> >;
00920         template struct KDTreeUnbalancedPtInLeavesExplicitBoundsStack<double, Eigen::Map<const Eigen::Matrix3Xd, Eigen::Aligned> >;
00921 }


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