47 #ifndef NANOFLANN_HPP_ 48 #define NANOFLANN_HPP_ 62 #define NANOFLANN_VERSION 0x130 65 #if !defined(NOMINMAX) && \ 66 (defined(_WIN32) || defined(_WIN32_) || defined(WIN32) || defined(_WIN64)) 80 return static_cast<T
>(3.14159265358979323846);
87 template <
typename T,
typename =
int>
struct has_resize : std::false_type {};
93 template <
typename T,
typename =
int>
struct has_assign : std::false_type {};
102 template <
typename Container>
103 inline typename std::enable_if<has_resize<Container>::value,
void>::type
104 resize(Container &c,
const size_t nElements) {
112 template <
typename Container>
113 inline typename std::enable_if<!has_resize<Container>::value,
void>::type
114 resize(Container &c,
const size_t nElements) {
115 if (nElements != c.size())
116 throw std::logic_error(
"Try to change the size of a std::array.");
122 template <
typename Container,
typename T>
123 inline typename std::enable_if<has_assign<Container>::value,
void>::type
124 assign(Container &c,
const size_t nElements,
const T &value) {
125 c.assign(nElements, value);
131 template <
typename Container,
typename T>
132 inline typename std::enable_if<!has_assign<Container>::value,
void>::type
133 assign(Container &c,
const size_t nElements,
const T &value) {
134 for (
size_t i = 0; i < nElements; i++)
140 template <
typename _DistanceType,
typename _IndexType = size_t,
141 typename _CountType =
size_t>
156 : indices(0), dists(0), capacity(capacity_), count(0) {}
158 inline void init(IndexType *indices_, DistanceType *dists_) {
163 dists[capacity - 1] = (std::numeric_limits<DistanceType>::max)();
166 inline CountType
size()
const {
return count; }
168 inline bool full()
const {
return count == capacity; }
175 inline bool addPoint(DistanceType dist, IndexType index) {
177 for (i = count; i > 0; --i) {
178 #ifdef NANOFLANN_FIRST_MATCH // If defined and two points have the same 181 if ((dists[i - 1] > dist) ||
182 ((dist == dists[i - 1]) && (indices[i - 1] > index))) {
184 if (dists[i - 1] > dist) {
187 dists[i] = dists[i - 1];
188 indices[i] = indices[i - 1];
197 if (count < capacity)
204 inline DistanceType
worstDist()
const {
return dists[capacity - 1]; }
210 template <
typename PairType>
211 inline bool operator()(
const PairType &p1,
const PairType &p2)
const {
212 return p1.second < p2.second;
219 template <
typename _DistanceType,
typename _IndexType =
size_t>
231 DistanceType radius_,
232 std::vector<std::pair<IndexType, DistanceType>> &indices_dists)
233 : radius(radius_), m_indices_dists(indices_dists) {
237 inline void init() { clear(); }
238 inline void clear() { m_indices_dists.clear(); }
240 inline size_t size()
const {
return m_indices_dists.size(); }
242 inline bool full()
const {
return true; }
249 inline bool addPoint(DistanceType dist, IndexType index) {
251 m_indices_dists.push_back(std::make_pair(index, dist));
255 inline DistanceType
worstDist()
const {
return radius; }
262 if (m_indices_dists.empty())
263 throw std::runtime_error(
"Cannot invoke RadiusResultSet::worst_item() on " 264 "an empty list of results.");
266 typename std::vector<std::pair<IndexType, DistanceType>>::const_iterator
268 DistIt it = std::max_element(m_indices_dists.begin(), m_indices_dists.end(),
278 template <
typename T>
279 void save_value(FILE *stream,
const T &value,
size_t count = 1) {
280 fwrite(&value,
sizeof(value), count, stream);
283 template <
typename T>
285 size_t size = value.size();
286 fwrite(&size,
sizeof(
size_t), 1, stream);
287 fwrite(&value[0],
sizeof(T), size, stream);
290 template <
typename T>
292 size_t read_cnt = fread(&value,
sizeof(value), count, stream);
293 if (read_cnt != count) {
294 throw std::runtime_error(
"Cannot read from file");
298 template <
typename T>
void load_value(FILE *stream, std::vector<T> &value) {
300 size_t read_cnt = fread(&size,
sizeof(
size_t), 1, stream);
302 throw std::runtime_error(
"Cannot read from file");
305 read_cnt = fread(&value[0],
sizeof(T), size, stream);
306 if (read_cnt != size) {
307 throw std::runtime_error(
"Cannot read from file");
323 template <
class T,
class DataSource,
typename _DistanceType = T>
330 L1_Adaptor(
const DataSource &_data_source) : data_source(_data_source) {}
332 inline DistanceType
evalMetric(
const T *a,
const size_t b_idx,
size_t size,
333 DistanceType worst_dist = -1)
const {
334 DistanceType result = DistanceType();
335 const T *last = a + size;
336 const T *lastgroup = last - 3;
340 while (a < lastgroup) {
341 const DistanceType diff0 =
342 std::abs(a[0] - data_source.kdtree_get_pt(b_idx, d++));
343 const DistanceType diff1 =
344 std::abs(a[1] - data_source.kdtree_get_pt(b_idx, d++));
345 const DistanceType diff2 =
346 std::abs(a[2] - data_source.kdtree_get_pt(b_idx, d++));
347 const DistanceType diff3 =
348 std::abs(a[3] - data_source.kdtree_get_pt(b_idx, d++));
349 result += diff0 + diff1 + diff2 + diff3;
351 if ((worst_dist > 0) && (result > worst_dist)) {
357 result += std::abs(*a++ - data_source.kdtree_get_pt(b_idx, d++));
362 template <
typename U,
typename V>
363 inline DistanceType
accum_dist(
const U a,
const V b,
const size_t)
const {
364 return std::abs(a - b);
374 template <
class T,
class DataSource,
typename _DistanceType = T>
381 L2_Adaptor(
const DataSource &_data_source) : data_source(_data_source) {}
383 inline DistanceType
evalMetric(
const T *a,
const size_t b_idx,
size_t size,
384 DistanceType worst_dist = -1)
const {
385 DistanceType result = DistanceType();
386 const T *last = a + size;
387 const T *lastgroup = last - 3;
391 while (a < lastgroup) {
392 const DistanceType diff0 = a[0] - data_source.kdtree_get_pt(b_idx, d++);
393 const DistanceType diff1 = a[1] - data_source.kdtree_get_pt(b_idx, d++);
394 const DistanceType diff2 = a[2] - data_source.kdtree_get_pt(b_idx, d++);
395 const DistanceType diff3 = a[3] - data_source.kdtree_get_pt(b_idx, d++);
396 result += diff0 * diff0 + diff1 * diff1 + diff2 * diff2 + diff3 * diff3;
398 if ((worst_dist > 0) && (result > worst_dist)) {
404 const DistanceType diff0 = *a++ - data_source.kdtree_get_pt(b_idx, d++);
405 result += diff0 * diff0;
410 template <
typename U,
typename V>
411 inline DistanceType
accum_dist(
const U a,
const V b,
const size_t)
const {
412 return (a - b) * (a - b);
422 template <
class T,
class DataSource,
typename _DistanceType = T>
430 : data_source(_data_source) {}
432 inline DistanceType
evalMetric(
const T *a,
const size_t b_idx,
434 DistanceType result = DistanceType();
435 for (
size_t i = 0; i < size; ++i) {
436 const DistanceType
diff = a[i] - data_source.kdtree_get_pt(b_idx, i);
437 result += diff * diff;
442 template <
typename U,
typename V>
443 inline DistanceType
accum_dist(
const U a,
const V b,
const size_t)
const {
444 return (a - b) * (a - b);
454 template <
class T,
class DataSource,
typename _DistanceType = T>
461 SO2_Adaptor(
const DataSource &_data_source) : data_source(_data_source) {}
463 inline DistanceType
evalMetric(
const T *a,
const size_t b_idx,
465 return accum_dist(a[size - 1], data_source.kdtree_get_pt(b_idx, size - 1),
470 template <
typename U,
typename V>
471 inline DistanceType
accum_dist(
const U a,
const V b,
const size_t)
const {
472 DistanceType result = DistanceType(),
PI = pi_const<DistanceType>();
476 else if (result < -
PI)
488 template <
class T,
class DataSource,
typename _DistanceType = T>
496 : distance_L2_Simple(_data_source) {}
498 inline DistanceType
evalMetric(
const T *a,
const size_t b_idx,
500 return distance_L2_Simple.
evalMetric(a, b_idx, size);
503 template <
typename U,
typename V>
504 inline DistanceType
accum_dist(
const U a,
const V b,
const size_t idx)
const {
505 return distance_L2_Simple.
accum_dist(a, b, idx);
511 template <
class T,
class DataSource>
struct traits {
517 template <
class T,
class DataSource>
struct traits {
523 template <
class T,
class DataSource>
struct traits {
529 template <
class T,
class DataSource>
struct traits {
535 template <
class T,
class DataSource>
struct traits {
548 : leaf_max_size(_leaf_max_size) {}
557 SearchParams(
int checks_IGNORED_ = 32,
float eps_ = 0,
bool sorted_ =
true)
558 : checks(checks_IGNORED_), eps(eps_), sorted(sorted_) {}
578 template <
typename T>
inline T *
allocate(
size_t count = 1) {
579 T *mem =
static_cast<T *
>(::malloc(
sizeof(T) * count));
635 while (base !=
NULL) {
637 *(
static_cast<void **
>(base));
653 const size_t size = (req_size + (WORDSIZE - 1)) & ~(WORDSIZE - 1);
658 if (size > remaining) {
660 wastedMemory += remaining;
663 const size_t blocksize =
664 (size +
sizeof(
void *) + (WORDSIZE - 1) >
BLOCKSIZE)
665 ? size +
sizeof(
void *) + (WORDSIZE - 1)
669 void *m = ::malloc(blocksize);
671 fprintf(stderr,
"Failed to allocate memory.\n");
676 static_cast<void **
>(m)[0] = base;
683 remaining = blocksize -
sizeof(
void *) - shift;
684 loc = (
static_cast<char *
>(m) +
sizeof(
void *) + shift);
687 loc =
static_cast<char *
>(loc) + size;
702 template <
typename T> T *
allocate(
const size_t count = 1) {
703 T *mem =
static_cast<T *
>(this->malloc(
sizeof(T) * count));
737 template <
class Derived,
typename Distance,
class DatasetAdaptor,
int DIM = -1,
738 typename IndexType =
size_t>
746 obj.root_node =
NULL;
747 obj.m_size_at_index_build = 0;
813 size_t size(
const Derived &obj)
const {
return obj.m_size; }
817 return static_cast<size_t>(DIM > 0 ? DIM : obj.dim);
822 int component)
const {
823 return obj.dataset.kdtree_get_pt(idx, component);
831 return obj.pool.usedMemory + obj.pool.wastedMemory +
832 obj.dataset.kdtree_get_point_count() *
837 int element, ElementType &min_elem,
838 ElementType &max_elem) {
839 min_elem = dataset_get(obj, ind[0], element);
840 max_elem = dataset_get(obj, ind[0], element);
841 for (IndexType i = 1; i < count; ++i) {
842 ElementType val = dataset_get(obj, ind[i], element);
857 NodePtr
divideTree(Derived &obj,
const IndexType left,
const IndexType right,
859 NodePtr node = obj.pool.template allocate<Node>();
862 if ((right - left) <=
static_cast<IndexType
>(obj.m_leaf_max_size)) {
863 node->child1 = node->child2 =
NULL;
864 node->node_type.lr.left = left;
865 node->node_type.lr.right = right;
868 for (
int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) {
869 bbox[i].low = dataset_get(obj, obj.vind[left], i);
870 bbox[i].high = dataset_get(obj, obj.vind[left], i);
872 for (IndexType k = left + 1; k < right; ++k) {
873 for (
int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) {
874 if (bbox[i].low > dataset_get(obj, obj.vind[k], i))
875 bbox[i].low = dataset_get(obj, obj.vind[k], i);
876 if (bbox[i].high < dataset_get(obj, obj.vind[k], i))
877 bbox[i].high = dataset_get(obj, obj.vind[k], i);
884 middleSplit_(obj, &obj.vind[0] + left, right - left, idx, cutfeat, cutval,
887 node->node_type.sub.divfeat = cutfeat;
889 BoundingBox left_bbox(bbox);
890 left_bbox[cutfeat].high = cutval;
891 node->child1 = divideTree(obj, left, left + idx, left_bbox);
893 BoundingBox right_bbox(bbox);
894 right_bbox[cutfeat].low = cutval;
895 node->child2 = divideTree(obj, left + idx, right, right_bbox);
897 node->node_type.sub.divlow = left_bbox[cutfeat].high;
898 node->node_type.sub.divhigh = right_bbox[cutfeat].low;
900 for (
int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) {
901 bbox[i].low = std::min(left_bbox[i].low, right_bbox[i].low);
902 bbox[i].high = std::max(left_bbox[i].high, right_bbox[i].high);
910 IndexType &index,
int &cutfeat, DistanceType &cutval,
911 const BoundingBox &bbox) {
912 const DistanceType EPS =
static_cast<DistanceType
>(0.00001);
913 ElementType max_span = bbox[0].high - bbox[0].low;
914 for (
int i = 1; i < (DIM > 0 ? DIM : obj.dim); ++i) {
915 ElementType span = bbox[i].high - bbox[i].low;
916 if (span > max_span) {
920 ElementType max_spread = -1;
922 for (
int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) {
923 ElementType span = bbox[i].high - bbox[i].low;
924 if (span > (1 - EPS) * max_span) {
925 ElementType min_elem, max_elem;
926 computeMinMax(obj, ind, count, i, min_elem, max_elem);
927 ElementType spread = max_elem - min_elem;
929 if (spread > max_spread) {
936 DistanceType split_val = (bbox[cutfeat].low + bbox[cutfeat].high) / 2;
937 ElementType min_elem, max_elem;
938 computeMinMax(obj, ind, count, cutfeat, min_elem, max_elem);
940 if (split_val < min_elem)
942 else if (split_val > max_elem)
947 IndexType lim1, lim2;
948 planeSplit(obj, ind, count, cutfeat, cutval, lim1, lim2);
950 if (lim1 > count / 2)
952 else if (lim2 < count / 2)
967 void planeSplit(Derived &obj, IndexType *ind,
const IndexType count,
968 int cutfeat, DistanceType &cutval, IndexType &lim1,
972 IndexType right = count - 1;
974 while (left <= right && dataset_get(obj, ind[left], cutfeat) < cutval)
976 while (right && left <= right &&
977 dataset_get(obj, ind[right], cutfeat) >= cutval)
979 if (left > right || !right)
981 std::swap(ind[left], ind[right]);
991 while (left <= right && dataset_get(obj, ind[left], cutfeat) <= cutval)
993 while (right && left <= right &&
994 dataset_get(obj, ind[right], cutfeat) > cutval)
996 if (left > right || !right)
998 std::swap(ind[left], ind[right]);
1006 const ElementType *vec,
1009 DistanceType distsq = DistanceType();
1011 for (
int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) {
1012 if (vec[i] < obj.root_bbox[i].low) {
1013 dists[i] = obj.distance.accum_dist(vec[i], obj.root_bbox[i].low, i);
1016 if (vec[i] > obj.root_bbox[i].high) {
1017 dists[i] = obj.distance.accum_dist(vec[i], obj.root_bbox[i].high, i);
1026 if (tree->child1 !=
NULL) {
1027 save_tree(obj, stream, tree->child1);
1029 if (tree->child2 !=
NULL) {
1030 save_tree(obj, stream, tree->child2);
1035 tree = obj.pool.template allocate<Node>();
1037 if (tree->child1 !=
NULL) {
1038 load_tree(obj, stream, tree->child1);
1040 if (tree->child2 !=
NULL) {
1041 load_tree(obj, stream, tree->child2);
1056 save_tree(obj, stream, obj.root_node);
1070 load_tree(obj, stream, obj.root_node);
1114 template <
typename Distance,
class DatasetAdaptor,
int DIM = -1,
1115 typename IndexType =
size_t>
1118 KDTreeSingleIndexAdaptor<Distance, DatasetAdaptor, DIM, IndexType>,
1119 Distance, DatasetAdaptor, DIM, IndexType> {
1138 Distance, DatasetAdaptor, DIM, IndexType>
1171 const DatasetAdaptor &inputData,
1174 : dataset(inputData), index_params(params), distance(inputData) {
1175 BaseClassRef::root_node =
NULL;
1176 BaseClassRef::m_size = dataset.kdtree_get_point_count();
1177 BaseClassRef::m_size_at_index_build = BaseClassRef::m_size;
1178 BaseClassRef::dim = dimensionality;
1180 BaseClassRef::dim = DIM;
1181 BaseClassRef::m_leaf_max_size = params.leaf_max_size;
1191 BaseClassRef::m_size = dataset.kdtree_get_point_count();
1192 BaseClassRef::m_size_at_index_build = BaseClassRef::m_size;
1194 this->freeIndex(*
this);
1195 BaseClassRef::m_size_at_index_build = BaseClassRef::m_size;
1196 if (BaseClassRef::m_size == 0)
1198 computeBoundingBox(BaseClassRef::root_bbox);
1199 BaseClassRef::root_node =
1200 this->divideTree(*
this, 0, BaseClassRef::m_size,
1201 BaseClassRef::root_bbox);
1220 template <
typename RESULTSET>
1224 if (this->size(*
this) == 0)
1226 if (!BaseClassRef::root_node)
1227 throw std::runtime_error(
1228 "[nanoflann] findNeighbors() called before building the index.");
1229 float epsError = 1 + searchParams.
eps;
1233 auto zero =
static_cast<decltype(result.worstDist())
>(0);
1234 assign(dists, (DIM > 0 ? DIM : BaseClassRef::dim),
1236 DistanceType distsq = this->computeInitialDistances(*
this, vec, dists);
1237 searchLevel(result, vec, BaseClassRef::root_node, distsq, dists,
1240 return result.full();
1252 size_t knnSearch(
const ElementType *query_point,
const size_t num_closest,
1253 IndexType *out_indices, DistanceType *out_distances_sq,
1254 const int = 10)
const {
1256 resultSet.
init(out_indices, out_distances_sq);
1258 return resultSet.
size();
1279 std::vector<std::pair<IndexType, DistanceType>> &IndicesDists,
1282 const size_t nFound =
1283 radiusSearchCustomCallback(query_point, resultSet, searchParams);
1294 template <
class SEARCH_CALLBACK>
1296 const ElementType *query_point, SEARCH_CALLBACK &resultSet,
1298 this->findNeighbors(resultSet, query_point, searchParams);
1299 return resultSet.size();
1309 BaseClassRef::m_size = dataset.kdtree_get_point_count();
1310 if (BaseClassRef::vind.size() != BaseClassRef::m_size)
1311 BaseClassRef::vind.resize(BaseClassRef::m_size);
1312 for (
size_t i = 0; i < BaseClassRef::m_size; i++)
1313 BaseClassRef::vind[i] = i;
1317 resize(bbox, (DIM > 0 ? DIM : BaseClassRef::dim));
1318 if (dataset.kdtree_get_bbox(bbox)) {
1321 const size_t N = dataset.kdtree_get_point_count();
1323 throw std::runtime_error(
"[nanoflann] computeBoundingBox() called but " 1324 "no data points found.");
1325 for (
int i = 0; i < (DIM > 0 ? DIM : BaseClassRef::dim); ++i) {
1326 bbox[i].low = bbox[i].high = this->dataset_get(*
this, 0, i);
1328 for (
size_t k = 1; k < N; ++k) {
1329 for (
int i = 0; i < (DIM > 0 ? DIM : BaseClassRef::dim); ++i) {
1330 if (this->dataset_get(*
this, k, i) < bbox[i].low)
1331 bbox[i].low = this->dataset_get(*
this, k, i);
1332 if (this->dataset_get(*
this, k, i) > bbox[i].high)
1333 bbox[i].high = this->dataset_get(*
this, k, i);
1345 template <
class RESULTSET>
1347 const NodePtr node, DistanceType mindistsq,
1348 distance_vector_t &dists,
const float epsError)
const {
1353 DistanceType worst_dist = result_set.worstDist();
1354 for (IndexType i = node->
node_type.
lr.left; i < node->node_type.lr.right;
1356 const IndexType index = BaseClassRef::vind[i];
1357 DistanceType dist = distance.evalMetric(
1358 vec, index, (DIM > 0 ? DIM : BaseClassRef::dim));
1359 if (dist < worst_dist) {
1360 if (!result_set.addPoint(dist, BaseClassRef::vind[i])) {
1372 ElementType val = vec[idx];
1374 DistanceType diff2 = val - node->
node_type.
sub.divhigh;
1378 DistanceType cut_dist;
1379 if ((diff1 + diff2) < 0) {
1380 bestChild = node->
child1;
1381 otherChild = node->
child2;
1382 cut_dist = distance.accum_dist(val, node->
node_type.
sub.divhigh, idx);
1384 bestChild = node->
child2;
1385 otherChild = node->
child1;
1386 cut_dist = distance.accum_dist(val, node->
node_type.
sub.divlow, idx);
1390 if (!searchLevel(result_set, vec, bestChild, mindistsq, dists, epsError)) {
1396 DistanceType dst = dists[idx];
1397 mindistsq = mindistsq + cut_dist - dst;
1398 dists[idx] = cut_dist;
1399 if (mindistsq * epsError <= result_set.worstDist()) {
1400 if (!searchLevel(result_set, vec, otherChild, mindistsq, dists,
1417 void saveIndex(FILE *stream) { this->saveIndex_(*
this, stream); }
1424 void loadIndex(FILE *stream) { this->loadIndex_(*
this, stream); }
1464 template <
typename Distance,
class DatasetAdaptor,
int DIM = -1,
1465 typename IndexType =
size_t>
1468 Distance, DatasetAdaptor, DIM, IndexType>,
1469 Distance, DatasetAdaptor, DIM, IndexType> {
1485 Distance, DatasetAdaptor, DIM, IndexType>
1518 const int dimensionality,
const DatasetAdaptor &inputData,
1519 std::vector<int> &treeIndex_,
1522 : dataset(inputData), index_params(params), treeIndex(treeIndex_),
1523 distance(inputData) {
1524 BaseClassRef::root_node =
NULL;
1525 BaseClassRef::m_size = 0;
1526 BaseClassRef::m_size_at_index_build = 0;
1527 BaseClassRef::dim = dimensionality;
1529 BaseClassRef::dim = DIM;
1530 BaseClassRef::m_leaf_max_size = params.leaf_max_size;
1537 std::swap(BaseClassRef::vind, tmp.BaseClassRef::vind);
1538 std::swap(BaseClassRef::m_leaf_max_size, tmp.BaseClassRef::m_leaf_max_size);
1541 std::swap(BaseClassRef::m_size, tmp.BaseClassRef::m_size);
1542 std::swap(BaseClassRef::m_size_at_index_build,
1543 tmp.BaseClassRef::m_size_at_index_build);
1544 std::swap(BaseClassRef::root_node, tmp.BaseClassRef::root_node);
1545 std::swap(BaseClassRef::root_bbox, tmp.BaseClassRef::root_bbox);
1546 std::swap(BaseClassRef::pool, tmp.BaseClassRef::pool);
1554 BaseClassRef::m_size = BaseClassRef::vind.size();
1555 this->freeIndex(*
this);
1556 BaseClassRef::m_size_at_index_build = BaseClassRef::m_size;
1557 if (BaseClassRef::m_size == 0)
1559 computeBoundingBox(BaseClassRef::root_bbox);
1560 BaseClassRef::root_node =
1561 this->divideTree(*
this, 0, BaseClassRef::m_size,
1562 BaseClassRef::root_bbox);
1581 template <
typename RESULTSET>
1585 if (this->size(*
this) == 0)
1587 if (!BaseClassRef::root_node)
1589 float epsError = 1 + searchParams.
eps;
1592 distance_vector_t dists;
1594 assign(dists, (DIM > 0 ? DIM : BaseClassRef::dim),
1595 static_cast<typename distance_vector_t::value_type>(0));
1596 DistanceType distsq = this->computeInitialDistances(*
this, vec, dists);
1597 searchLevel(result, vec, BaseClassRef::root_node, distsq, dists,
1600 return result.full();
1612 size_t knnSearch(
const ElementType *query_point,
const size_t num_closest,
1613 IndexType *out_indices, DistanceType *out_distances_sq,
1614 const int = 10)
const {
1616 resultSet.
init(out_indices, out_distances_sq);
1618 return resultSet.
size();
1639 std::vector<std::pair<IndexType, DistanceType>> &IndicesDists,
1642 const size_t nFound =
1643 radiusSearchCustomCallback(query_point, resultSet, searchParams);
1654 template <
class SEARCH_CALLBACK>
1656 const ElementType *query_point, SEARCH_CALLBACK &resultSet,
1658 this->findNeighbors(resultSet, query_point, searchParams);
1659 return resultSet.size();
1666 resize(bbox, (DIM > 0 ? DIM : BaseClassRef::dim));
1668 if (dataset.kdtree_get_bbox(bbox)) {
1671 const size_t N = BaseClassRef::m_size;
1673 throw std::runtime_error(
"[nanoflann] computeBoundingBox() called but " 1674 "no data points found.");
1675 for (
int i = 0; i < (DIM > 0 ? DIM : BaseClassRef::dim); ++i) {
1676 bbox[i].low = bbox[i].high =
1677 this->dataset_get(*
this, BaseClassRef::vind[0], i);
1679 for (
size_t k = 1; k < N; ++k) {
1680 for (
int i = 0; i < (DIM > 0 ? DIM : BaseClassRef::dim); ++i) {
1681 if (this->dataset_get(*
this, BaseClassRef::vind[k], i) < bbox[i].low)
1682 bbox[i].low = this->dataset_get(*
this, BaseClassRef::vind[k], i);
1683 if (this->dataset_get(*
this, BaseClassRef::vind[k], i) > bbox[i].high)
1684 bbox[i].high = this->dataset_get(*
this, BaseClassRef::vind[k], i);
1694 template <
class RESULTSET>
1696 const NodePtr node, DistanceType mindistsq,
1697 distance_vector_t &dists,
const float epsError)
const {
1702 DistanceType worst_dist = result_set.worstDist();
1703 for (IndexType i = node->
node_type.
lr.left; i < node->node_type.lr.right;
1705 const IndexType index = BaseClassRef::vind[i];
1706 if (treeIndex[index] == -1)
1708 DistanceType dist = distance.evalMetric(
1709 vec, index, (DIM > 0 ? DIM : BaseClassRef::dim));
1710 if (dist < worst_dist) {
1711 if (!result_set.addPoint(
1712 static_cast<typename RESULTSET::DistanceType>(dist),
1713 static_cast<typename RESULTSET::IndexType>(
1714 BaseClassRef::vind[i]))) {
1726 ElementType val = vec[idx];
1728 DistanceType diff2 = val - node->
node_type.
sub.divhigh;
1732 DistanceType cut_dist;
1733 if ((diff1 + diff2) < 0) {
1734 bestChild = node->
child1;
1735 otherChild = node->
child2;
1736 cut_dist = distance.accum_dist(val, node->
node_type.
sub.divhigh, idx);
1738 bestChild = node->
child2;
1739 otherChild = node->
child1;
1740 cut_dist = distance.accum_dist(val, node->
node_type.
sub.divlow, idx);
1744 searchLevel(result_set, vec, bestChild, mindistsq, dists, epsError);
1746 DistanceType dst = dists[idx];
1747 mindistsq = mindistsq + cut_dist - dst;
1748 dists[idx] = cut_dist;
1749 if (mindistsq * epsError <= result_set.worstDist()) {
1750 searchLevel(result_set, vec, otherChild, mindistsq, dists, epsError);
1761 void saveIndex(FILE *stream) { this->saveIndex_(*
this, stream); }
1768 void loadIndex(FILE *stream) { this->loadIndex_(*
this, stream); }
1785 template <
typename Distance,
class DatasetAdaptor,
int DIM = -1,
1786 typename IndexType =
size_t>
1834 std::vector<my_kd_tree_t> index_(
1835 treeCount, my_kd_tree_t(dim , dataset, treeIndex, index_params));
1857 const DatasetAdaptor &inputData,
1860 const size_t maximumPointCount = 1000000000U)
1861 : dataset(inputData), index_params(params), distance(inputData) {
1862 treeCount =
static_cast<size_t>(std::log2(maximumPointCount));
1864 dim = dimensionality;
1870 const size_t num_initial_points = dataset.kdtree_get_point_count();
1871 if (num_initial_points > 0) {
1872 addPoints(0, num_initial_points - 1);
1879 IndexType> &) =
delete;
1883 size_t count = end - start + 1;
1884 treeIndex.resize(treeIndex.size() + count);
1885 for (IndexType idx = start; idx <= end; idx++) {
1886 int pos = First0Bit(pointCount);
1887 index[pos].vind.clear();
1888 treeIndex[pointCount] = pos;
1889 for (
int i = 0; i < pos; i++) {
1890 for (
int j = 0; j < static_cast<int>(index[i].vind.size()); j++) {
1891 index[pos].vind.push_back(index[i].vind[j]);
1892 if (treeIndex[index[i].vind[j]] != -1)
1893 treeIndex[index[i].vind[j]] = pos;
1895 index[i].vind.clear();
1896 index[i].freeIndex(index[i]);
1898 index[pos].vind.push_back(idx);
1899 index[pos].buildIndex();
1906 if (idx >= pointCount)
1908 treeIndex[idx] = -1;
1924 template <
typename RESULTSET>
1927 for (
size_t i = 0; i < treeCount; i++) {
1928 index[i].findNeighbors(result, &vec[0], searchParams);
1930 return result.full();
1955 typedef typename MatrixType::Scalar
num_t;
1958 typename Distance::template traits<num_t, self_t>::distance_t
metric_t;
1960 MatrixType::ColsAtCompileTime, IndexType>
1968 const std::reference_wrapper<const MatrixType> &mat,
1969 const int leaf_max_size = 10)
1970 : m_data_matrix(mat) {
1971 const auto dims = mat.get().cols();
1972 if (
size_t(dims) != dimensionality)
1973 throw std::runtime_error(
1974 "Error: 'dimensionality' must match column count in data matrix");
1975 if (DIM > 0 &&
int(dims) != DIM)
1976 throw std::runtime_error(
1977 "Data set dimensionality does not match the 'DIM' template argument");
1979 new index_t(static_cast<int>(dims), *
this ,
1998 inline void query(
const num_t *query_point,
const size_t num_closest,
1999 IndexType *out_indices, num_t *out_distances_sq,
2000 const int = 10)
const {
2002 resultSet.
init(out_indices, out_distances_sq);
2014 return m_data_matrix.get().rows();
2019 return m_data_matrix.get().coeff(idx, IndexType(dim));
int First0Bit(IndexType num)
KDTreeSingleIndexAdaptorParams(size_t _leaf_max_size=10)
size_t veclen(const Derived &obj)
void computeBoundingBox(BoundingBox &bbox)
BaseClassRef::distance_vector_t distance_vector_t
std::vector< int > & treeIndex
size_t kdtree_get_point_count() const
L2_Simple_Adaptor< T, DataSource > distance_L2_Simple
const std::reference_wrapper< const MatrixType > m_data_matrix
size_t radiusSearch(const ElementType *query_point, const DistanceType &radius, std::vector< std::pair< IndexType, DistanceType >> &IndicesDists, const SearchParams &searchParams) const
void addPoints(IndexType start, IndexType end)
BaseClassRef::Interval Interval
BaseClassRef::BoundingBox BoundingBox
void computeBoundingBox(BoundingBox &bbox)
L2_Simple_Adaptor< T, DataSource > distance_t
void middleSplit_(Derived &obj, IndexType *ind, IndexType count, IndexType &index, int &cutfeat, DistanceType &cutval, const BoundingBox &bbox)
KDTreeEigenMatrixAdaptor< MatrixType, DIM, Distance > self_t
SO3_Adaptor< T, DataSource > distance_t
void init(const M_string &remappings)
KDTreeSingleIndexAdaptor(const int dimensionality, const DatasetAdaptor &inputData, const KDTreeSingleIndexAdaptorParams ¶ms=KDTreeSingleIndexAdaptorParams())
BaseClassRef::DistanceType DistanceType
L2_Simple_Adaptor(const DataSource &_data_source)
BaseClassRef::BoundingBox BoundingBox
KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, DIM > index_container_t
L1_Adaptor(const DataSource &_data_source)
void load_tree(Derived &obj, FILE *stream, NodePtr &tree)
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
const DistanceType radius
SO2_Adaptor(const DataSource &_data_source)
size_t radiusSearch(const ElementType *query_point, const DistanceType &radius, std::vector< std::pair< IndexType, DistanceType >> &IndicesDists, const SearchParams &searchParams) const
const DatasetAdaptor & dataset
The source of our data.
size_t size(const Derived &obj) const
const DatasetAdaptor & dataset
The source of our data.
const DataSource & data_source
void init(IndexType *indices_, DistanceType *dists_)
DistanceType worstDist() const
void load_value(FILE *stream, T &value, size_t count=1)
size_t knnSearch(const ElementType *query_point, const size_t num_closest, IndexType *out_indices, DistanceType *out_distances_sq, const int=10) const
size_t m_size_at_index_build
const DatasetAdaptor & dataset
The source of our data.
KDTreeSingleIndexAdaptorParams index_params
int divfeat
Dimension used for subdivision.
SO2_Adaptor< T, DataSource > distance_t
KDTreeEigenMatrixAdaptor(const size_t dimensionality, const std::reference_wrapper< const MatrixType > &mat, const int leaf_max_size=10)
Constructor: takes a const ref to the matrix object with the data points.
Distance::ElementType ElementType
Distance::DistanceType DistanceType
void freeIndex(Derived &obj)
std::enable_if< has_resize< Container >::value, void >::type resize(Container &c, const size_t nElements)
void saveIndex(FILE *stream)
KDTreeSingleIndexAdaptorParams index_params
DistanceType accum_dist(const U a, const V b, const size_t) const
array_or_vector_selector< DIM, DistanceType >::container_t distance_vector_t
void loadIndex(FILE *stream)
Distance::ElementType ElementType
void loadIndex_(Derived &obj, FILE *stream)
std::array< T, DIM > container_t
DistanceType accum_dist(const U a, const V b, const size_t) const
void searchLevel(RESULTSET &result_set, const ElementType *vec, const NodePtr node, DistanceType mindistsq, distance_vector_t &dists, const float epsError) const
size_t knnSearch(const ElementType *query_point, const size_t num_closest, IndexType *out_indices, DistanceType *out_distances_sq, const int=10) const
IndexType right
Indices of points in leaf node.
void query(const num_t *query_point, const size_t num_closest, IndexType *out_indices, num_t *out_distances_sq, const int=10) const
Distance::DistanceType DistanceType
KNNResultSet(CountType capacity_)
std::vector< T > container_t
const DataSource & data_source
const self_t & derived() const
_DistanceType DistanceType
Distance::template traits< num_t, self_t >::distance_t metric_t
T * allocate(const size_t count=1)
MatrixType::Index IndexType
DistanceType worstDist() const
DistanceType evalMetric(const T *a, const size_t b_idx, size_t size, DistanceType worst_dist=-1) const
RadiusResultSet(DistanceType radius_, std::vector< std::pair< IndexType, DistanceType >> &indices_dists)
BaseClassRef::DistanceType DistanceType
DistanceType evalMetric(const T *a, const size_t b_idx, size_t size) const
BaseClassRef::ElementType ElementType
size_t m_size
Number of current points in the dataset.
nanoflann::KDTreeBaseClass< nanoflann::KDTreeSingleIndexAdaptor< Distance, DatasetAdaptor, DIM, IndexType >, Distance, DatasetAdaptor, DIM, IndexType > BaseClassRef
const DataSource & data_source
std::vector< std::pair< IndexType, DistanceType > > & m_indices_dists
T * allocate(size_t count=1)
KDTreeSingleIndexDynamicAdaptor_ operator=(const KDTreeSingleIndexDynamicAdaptor_ &rhs)
void saveIndex(FILE *stream)
BaseClassRef::distance_vector_t distance_vector_t
NodePtr divideTree(Derived &obj, const IndexType left, const IndexType right, BoundingBox &bbox)
KDTreeSingleIndexAdaptor< metric_t, self_t, MatrixType::ColsAtCompileTime, IndexType > index_t
void saveIndex_(Derived &obj, FILE *stream)
_DistanceType DistanceType
Node * child2
Child nodes (both=NULL mean its a leaf node)
DistanceType accum_dist(const U a, const V b, const size_t idx) const
_DistanceType DistanceType
void planeSplit(Derived &obj, IndexType *ind, const IndexType count, int cutfeat, DistanceType &cutval, IndexType &lim1, IndexType &lim2)
DistanceType evalMetric(const T *a, const size_t b_idx, size_t size, DistanceType worst_dist=-1) const
KDTreeSingleIndexDynamicAdaptor(const int dimensionality, const DatasetAdaptor &inputData, const KDTreeSingleIndexAdaptorParams ¶ms=KDTreeSingleIndexAdaptorParams(), const size_t maximumPointCount=1000000000U)
bool searchLevel(RESULTSET &result_set, const ElementType *vec, const NodePtr node, DistanceType mindistsq, distance_vector_t &dists, const float epsError) const
DistanceType computeInitialDistances(const Derived &obj, const ElementType *vec, distance_vector_t &dists) const
int dim
Dimensionality of each data point.
size_t radiusSearchCustomCallback(const ElementType *query_point, SEARCH_CALLBACK &resultSet, const SearchParams &searchParams=SearchParams()) const
DistanceType evalMetric(const T *a, const size_t b_idx, size_t size) const
bool addPoint(DistanceType dist, IndexType index)
BaseClassRef::ElementType ElementType
bool findNeighbors(RESULTSET &result, const ElementType *vec, const SearchParams &searchParams) const
struct nanoflann::KDTreeBaseClass::Node::@0::nonleaf sub
_DistanceType DistanceType
std::vector< index_container_t > index
const KDTreeSingleIndexAdaptorParams index_params
_DistanceType DistanceType
L2_Adaptor(const DataSource &_data_source)
bool findNeighbors(RESULTSET &result, const ElementType *vec, const SearchParams &searchParams) const
L1_Adaptor< T, DataSource > distance_t
nanoflann::KDTreeBaseClass< nanoflann::KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, DIM, IndexType >, Distance, DatasetAdaptor, DIM, IndexType > BaseClassRef
void * malloc(const size_t req_size)
DistanceType evalMetric(const T *a, const size_t b_idx, size_t size) const
size_t radiusSearchCustomCallback(const ElementType *query_point, SEARCH_CALLBACK &resultSet, const SearchParams &searchParams=SearchParams()) const
void removePoint(size_t idx)
~KDTreeEigenMatrixAdaptor()
KDTreeSingleIndexDynamicAdaptor_(const int dimensionality, const DatasetAdaptor &inputData, std::vector< int > &treeIndex_, const KDTreeSingleIndexAdaptorParams ¶ms=KDTreeSingleIndexAdaptorParams())
const DataSource & data_source
std::vector< int > treeIndex
ElementType dataset_get(const Derived &obj, size_t idx, int component) const
Helper accessor to the dataset points:
void computeMinMax(const Derived &obj, IndexType *ind, IndexType count, int element, ElementType &min_elem, ElementType &max_elem)
L2_Adaptor< T, DataSource > distance_t
void save_value(FILE *stream, const T &value, size_t count=1)
_DistanceType DistanceType
SearchParams(int checks_IGNORED_=32, float eps_=0, bool sorted_=true)
array_or_vector_selector< DIM, Interval >::container_t BoundingBox
bool operator()(const PairType &p1, const PairType &p2) const
BaseClassRef::Interval Interval
std::pair< IndexType, DistanceType > worst_item() const
void loadIndex(FILE *stream)
void save_tree(Derived &obj, FILE *stream, NodePtr tree)
struct nanoflann::KDTreeBaseClass::Node::@0::leaf lr
size_t usedMemory(Derived &obj)
num_t kdtree_get_pt(const IndexType idx, size_t dim) const
_DistanceType DistanceType
SO3_Adaptor(const DataSource &_data_source)
float eps
search for eps-approximate neighbours (default: 0)
const std::vector< index_container_t > & getAllIndices() const
bool addPoint(DistanceType dist, IndexType index)
bool findNeighbors(RESULTSET &result, const ElementType *vec, const SearchParams &searchParams) const
bool kdtree_get_bbox(BBOX &) const
std::vector< IndexType > vind
union nanoflann::KDTreeBaseClass::Node::@0 node_type
DistanceType accum_dist(const U a, const V b, const size_t) const
std::enable_if< has_assign< Container >::value, void >::type assign(Container &c, const size_t nElements, const T &value)
DistanceType accum_dist(const U a, const V b, const size_t) const