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
00033
00034 #ifndef __VCGLIB_AABBBINARYTREE_KCLOSEST_H
00035 #define __VCGLIB_AABBBINARYTREE_KCLOSEST_H
00036
00037
00038 #include <queue>
00039 #include <deque>
00040
00041
00042 #include <vcg/space/index/aabb_binary_tree/base.h>
00043 #include <wrap/utils.h>
00044
00045
00046
00047 namespace vcg {
00048
00049 template <class TREETYPE>
00050 class AABBBinaryTreeKClosest {
00051 public:
00052 typedef AABBBinaryTreeKClosest<TREETYPE> ClassType;
00053 typedef TREETYPE TreeType;
00054 typedef typename TreeType::ScalarType ScalarType;
00055 typedef typename TreeType::CoordType CoordType;
00056 typedef typename TreeType::NodeType NodeType;
00057 typedef typename TreeType::ObjPtr ObjPtr;
00058
00059 protected:
00060 class ClosestObjType {
00061 public:
00062 ObjPtr pObj;
00063 ScalarType minDist;
00064 CoordType closestPt;
00065 };
00066
00067 class CompareClosest {
00068 public:
00069 bool operator () (const ClosestObjType & a, const ClosestObjType & b) {
00070 return (a.minDist < b.minDist);
00071 }
00072 };
00073
00074 typedef std::priority_queue<ClosestObjType, std::deque<ClosestObjType>, CompareClosest> PQueueType;
00075
00076 public:
00077 template <class OBJPOINTDISTANCEFUNCT, class OBJPTRCONTAINERTYPE, class DISTCONTAINERTYPE, class POINTCONTAINERTYPE>
00078 static inline unsigned int KClosest(TreeType & tree, OBJPOINTDISTANCEFUNCT & getPointDistance, const unsigned int k, const CoordType & p, const ScalarType & maxDist, OBJPTRCONTAINERTYPE & objects, DISTCONTAINERTYPE & distances, POINTCONTAINERTYPE & points) {
00079 typedef std::vector<NodeType *> NodePtrVector;
00080 typedef typename NodePtrVector::const_iterator NodePtrVector_ci;
00081
00082 if (k == 0) {
00083 return (0);
00084 }
00085
00086 NodeType * pRoot = tree.pRoot;
00087
00088 if (pRoot == 0) {
00089 return (0);
00090 }
00091
00092 PQueueType pq;
00093 ScalarType mindmax = maxDist;
00094
00095 ClassType::DepthFirstCollect(pRoot, getPointDistance, k, p, mindmax, pq);
00096
00097 const unsigned int sz = (unsigned int)(pq.size());
00098
00099 while (!pq.empty()) {
00100 ClosestObjType cobj = pq.top();
00101 pq.pop();
00102 objects.push_back(cobj.pObj);
00103 distances.push_back(cobj.minDist);
00104 points.push_back(cobj.closestPt);
00105 }
00106
00107 return (sz);
00108 }
00109
00110 protected:
00111 template <class OBJPOINTDISTANCEFUNCT>
00112 static void DepthFirstCollect(NodeType * node, OBJPOINTDISTANCEFUNCT & getPointDistance, const unsigned int k, const CoordType & p, ScalarType & mindmax, PQueueType & pq) {
00113 const CoordType dc = Abs(p - node->boxCenter);
00114
00115 if (pq.size() >= k) {
00116 const ScalarType dmin = LowClampToZero(dc - node->boxHalfDims).SquaredNorm();
00117 if (dmin >= mindmax) {
00118 return;
00119 }
00120 }
00121
00122 if (node->IsLeaf()) {
00123 bool someInserted = true;
00124 for (typename TreeType::ObjPtrVectorConstIterator si=node->oBegin; si!=node->oEnd; ++si) {
00125 ScalarType minDst = (pq.size() >= k) ? (pq.top().minDist) : (mindmax);
00126 ClosestObjType cobj;
00127 if (getPointDistance(*(*si), p, minDst, cobj.closestPt)) {
00128 someInserted = true;
00129 cobj.pObj = (*si);
00130 cobj.minDist = minDst;
00131 if (pq.size() >= k) {
00132 pq.pop();
00133 }
00134 pq.push(cobj);
00135 }
00136 }
00137 if (someInserted) {
00138 if (pq.size() >= k) {
00139 const ScalarType dmax = pq.top().minDist;
00140 const ScalarType sqdmax = dmax * dmax;
00141 if (sqdmax < mindmax) {
00142 mindmax = sqdmax;
00143 }
00144 }
00145 }
00146 }
00147 else {
00148 if (node->children[0] != 0) {
00149 ClassType::DepthFirstCollect(node->children[0], getPointDistance, k, p, mindmax, pq);
00150 }
00151 if (node->children[1] != 0) {
00152 ClassType::DepthFirstCollect(node->children[1], getPointDistance, k, p, mindmax, pq);
00153 }
00154 }
00155 }
00156
00157 };
00158
00159 }
00160
00161 #endif // #ifndef __VCGLIB_AABBBINARYTREE_KCLOSEST_H