47 #ifndef NANOFLANN_HPP_ 48 #define NANOFLANN_HPP_ 62 #define NANOFLANN_VERSION 0x132 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>
144 typedef _DistanceType DistanceType;
145 typedef _IndexType IndexType;
146 typedef _CountType CountType;
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>
222 typedef _DistanceType DistanceType;
223 typedef _IndexType IndexType;
226 const DistanceType radius;
228 std::vector<std::pair<IndexType, DistanceType>> &m_indices_dists;
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; }
261 std::pair<IndexType, DistanceType> worst_item()
const {
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>
284 void save_value(FILE *stream,
const std::vector<T> &value) {
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>
291 void load_value(FILE *stream, T &value,
size_t count = 1) {
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>
325 typedef T ElementType;
326 typedef _DistanceType DistanceType;
328 const DataSource &data_source;
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 {
374 template <
class T,
class DataSource,
typename _DistanceType = T>
376 typedef T ElementType;
377 typedef _DistanceType DistanceType;
379 const DataSource &data_source;
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>
424 typedef T ElementType;
425 typedef _DistanceType DistanceType;
427 const DataSource &data_source;
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();
473 DistanceType
PI = pi_const<DistanceType>();
477 else if (result < -PI)
489 template <
class T,
class DataSource,
typename _DistanceType = T>
497 : distance_L2_Simple(_data_source) {}
499 inline DistanceType
evalMetric(
const T *a,
const size_t b_idx,
501 return distance_L2_Simple.evalMetric(a, b_idx, size);
504 template <
typename U,
typename V>
505 inline DistanceType
accum_dist(
const U a,
const V b,
const size_t idx)
const {
506 return distance_L2_Simple.
accum_dist(a, b, idx);
512 template <
class T,
class DataSource>
struct traits {
518 template <
class T,
class DataSource>
struct traits {
524 template <
class T,
class DataSource>
struct traits {
530 template <
class T,
class DataSource>
struct traits {
536 template <
class T,
class DataSource>
struct traits {
549 : leaf_max_size(_leaf_max_size) {}
551 size_t leaf_max_size;
558 SearchParams(
int checks_IGNORED_ = 32,
float eps_ = 0,
bool sorted_ =
true)
559 : checks(checks_IGNORED_), eps(eps_), sorted(sorted_) {}
579 template <
typename T>
inline T *
allocate(
size_t count = 1) {
580 T *mem =
static_cast<T *
>(::malloc(
sizeof(T) * count));
613 void internal_init() {
636 while (base !=
NULL) {
638 *(
static_cast<void **
>(base));
649 void *malloc(
const size_t req_size) {
654 const size_t size = (req_size + (WORDSIZE - 1)) & ~(WORDSIZE - 1);
659 if (size > remaining) {
661 wastedMemory += remaining;
664 const size_t blocksize =
665 (size +
sizeof(
void *) + (WORDSIZE - 1) >
BLOCKSIZE)
666 ? size +
sizeof(
void *) + (WORDSIZE - 1)
670 void *m = ::malloc(blocksize);
672 fprintf(stderr,
"Failed to allocate memory.\n");
673 throw std::bad_alloc();
677 static_cast<void **
>(m)[0] = base;
684 remaining = blocksize -
sizeof(
void *) - shift;
685 loc = (
static_cast<char *
>(m) +
sizeof(
void *) + shift);
688 loc =
static_cast<char *
>(loc) + size;
703 template <
typename T> T *
allocate(
const size_t count = 1) {
704 T *mem =
static_cast<T *
>(this->malloc(
sizeof(T) * count));
738 template <
class Derived,
typename Distance,
class DatasetAdaptor,
int DIM = -1,
739 typename IndexType =
size_t>
747 obj.root_node =
NULL;
748 obj.m_size_at_index_build = 0;
814 size_t size(
const Derived &obj)
const {
return obj.m_size; }
818 return static_cast<size_t>(DIM > 0 ? DIM : obj.dim);
823 int component)
const {
824 return obj.dataset.kdtree_get_pt(idx, component);
832 return obj.pool.usedMemory + obj.pool.wastedMemory +
833 obj.dataset.kdtree_get_point_count() *
838 int element, ElementType &min_elem,
839 ElementType &max_elem) {
840 min_elem = dataset_get(obj, ind[0], element);
841 max_elem = dataset_get(obj, ind[0], element);
842 for (IndexType i = 1; i < count; ++i) {
843 ElementType val = dataset_get(obj, ind[i], element);
858 NodePtr
divideTree(Derived &obj,
const IndexType left,
const IndexType right,
860 NodePtr node = obj.pool.template allocate<Node>();
863 if ((right - left) <=
static_cast<IndexType
>(obj.m_leaf_max_size)) {
864 node->child1 = node->child2 =
NULL;
865 node->node_type.lr.left = left;
866 node->node_type.lr.right = right;
869 for (
int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) {
870 bbox[i].low = dataset_get(obj, obj.vind[left], i);
871 bbox[i].high = dataset_get(obj, obj.vind[left], i);
873 for (IndexType k = left + 1; k < right; ++k) {
874 for (
int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) {
875 if (bbox[i].low > dataset_get(obj, obj.vind[k], i))
876 bbox[i].low = dataset_get(obj, obj.vind[k], i);
877 if (bbox[i].high < dataset_get(obj, obj.vind[k], i))
878 bbox[i].high = dataset_get(obj, obj.vind[k], i);
885 middleSplit_(obj, &obj.vind[0] + left, right - left, idx, cutfeat, cutval,
888 node->node_type.sub.divfeat = cutfeat;
890 BoundingBox left_bbox(bbox);
891 left_bbox[cutfeat].high = cutval;
892 node->child1 = divideTree(obj, left, left + idx, left_bbox);
894 BoundingBox right_bbox(bbox);
895 right_bbox[cutfeat].low = cutval;
896 node->child2 = divideTree(obj, left + idx, right, right_bbox);
898 node->node_type.sub.divlow = left_bbox[cutfeat].high;
899 node->node_type.sub.divhigh = right_bbox[cutfeat].low;
901 for (
int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) {
902 bbox[i].low = std::min(left_bbox[i].low, right_bbox[i].low);
903 bbox[i].high = std::max(left_bbox[i].high, right_bbox[i].high);
911 IndexType &index,
int &cutfeat, DistanceType &cutval,
912 const BoundingBox &bbox) {
913 const DistanceType EPS =
static_cast<DistanceType
>(0.00001);
914 ElementType max_span = bbox[0].high - bbox[0].low;
915 for (
int i = 1; i < (DIM > 0 ? DIM : obj.dim); ++i) {
916 ElementType span = bbox[i].high - bbox[i].low;
917 if (span > max_span) {
921 ElementType max_spread = -1;
923 for (
int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) {
924 ElementType span = bbox[i].high - bbox[i].low;
925 if (span > (1 - EPS) * max_span) {
926 ElementType min_elem, max_elem;
927 computeMinMax(obj, ind, count, i, min_elem, max_elem);
928 ElementType spread = max_elem - min_elem;
930 if (spread > max_spread) {
937 DistanceType split_val = (bbox[cutfeat].low + bbox[cutfeat].high) / 2;
938 ElementType min_elem, max_elem;
939 computeMinMax(obj, ind, count, cutfeat, min_elem, max_elem);
941 if (split_val < min_elem)
943 else if (split_val > max_elem)
948 IndexType lim1, lim2;
949 planeSplit(obj, ind, count, cutfeat, cutval, lim1, lim2);
951 if (lim1 > count / 2)
953 else if (lim2 < count / 2)
968 void planeSplit(Derived &obj, IndexType *ind,
const IndexType count,
969 int cutfeat, DistanceType &cutval, IndexType &lim1,
973 IndexType right = count - 1;
975 while (left <= right && dataset_get(obj, ind[left], cutfeat) < cutval)
977 while (right && left <= right &&
978 dataset_get(obj, ind[right], cutfeat) >= cutval)
980 if (left > right || !right)
982 std::swap(ind[left], ind[right]);
992 while (left <= right && dataset_get(obj, ind[left], cutfeat) <= cutval)
994 while (right && left <= right &&
995 dataset_get(obj, ind[right], cutfeat) > cutval)
997 if (left > right || !right)
999 std::swap(ind[left], ind[right]);
1007 const ElementType *vec,
1010 DistanceType distsq = DistanceType();
1012 for (
int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) {
1013 if (vec[i] < obj.root_bbox[i].low) {
1014 dists[i] = obj.distance.accum_dist(vec[i], obj.root_bbox[i].low, i);
1017 if (vec[i] > obj.root_bbox[i].high) {
1018 dists[i] = obj.distance.accum_dist(vec[i], obj.root_bbox[i].high, i);
1027 if (tree->child1 !=
NULL) {
1028 save_tree(obj, stream, tree->child1);
1030 if (tree->child2 !=
NULL) {
1031 save_tree(obj, stream, tree->child2);
1036 tree = obj.pool.template allocate<Node>();
1038 if (tree->child1 !=
NULL) {
1039 load_tree(obj, stream, tree->child1);
1041 if (tree->child2 !=
NULL) {
1042 load_tree(obj, stream, tree->child2);
1057 save_tree(obj, stream, obj.root_node);
1071 load_tree(obj, stream, obj.root_node);
1115 template <
typename Distance,
class DatasetAdaptor,
int DIM = -1,
1116 typename IndexType =
size_t>
1119 KDTreeSingleIndexAdaptor<Distance, DatasetAdaptor, DIM, IndexType>,
1120 Distance, DatasetAdaptor, DIM, IndexType> {
1130 const DatasetAdaptor &dataset;
1139 Distance, DatasetAdaptor, DIM, IndexType>
1142 typedef typename BaseClassRef::ElementType
ElementType;
1143 typedef typename BaseClassRef::DistanceType DistanceType;
1145 typedef typename BaseClassRef::Node Node;
1148 typedef typename BaseClassRef::Interval Interval;
1151 typedef typename BaseClassRef::BoundingBox
BoundingBox;
1172 const DatasetAdaptor &inputData,
1175 : dataset(inputData), index_params(params), distance(inputData) {
1176 BaseClassRef::root_node =
NULL;
1177 BaseClassRef::m_size = dataset.kdtree_get_point_count();
1178 BaseClassRef::m_size_at_index_build = BaseClassRef::m_size;
1179 BaseClassRef::dim = dimensionality;
1181 BaseClassRef::dim = DIM;
1182 BaseClassRef::m_leaf_max_size = params.leaf_max_size;
1192 BaseClassRef::m_size = dataset.kdtree_get_point_count();
1193 BaseClassRef::m_size_at_index_build = BaseClassRef::m_size;
1195 this->freeIndex(*
this);
1196 BaseClassRef::m_size_at_index_build = BaseClassRef::m_size;
1197 if (BaseClassRef::m_size == 0)
1199 computeBoundingBox(BaseClassRef::root_bbox);
1200 BaseClassRef::root_node =
1201 this->divideTree(*
this, 0, BaseClassRef::m_size,
1202 BaseClassRef::root_bbox);
1221 template <
typename RESULTSET>
1222 bool findNeighbors(RESULTSET &result,
const ElementType *vec,
1225 if (this->size(*
this) == 0)
1227 if (!BaseClassRef::root_node)
1228 throw std::runtime_error(
1229 "[nanoflann] findNeighbors() called before building the index.");
1230 float epsError = 1 + searchParams.
eps;
1234 auto zero =
static_cast<decltype(result.worstDist())
>(0);
1235 assign(dists, (DIM > 0 ? DIM : BaseClassRef::dim),
1237 DistanceType distsq = this->computeInitialDistances(*
this, vec, dists);
1238 searchLevel(result, vec, BaseClassRef::root_node, distsq, dists,
1241 return result.full();
1253 size_t knnSearch(
const ElementType *query_point,
const size_t num_closest,
1254 IndexType *out_indices, DistanceType *out_distances_sq,
1255 const int = 10)
const {
1257 resultSet.
init(out_indices, out_distances_sq);
1259 return resultSet.
size();
1279 radiusSearch(
const ElementType *query_point,
const DistanceType &radius,
1280 std::vector<std::pair<IndexType, DistanceType>> &IndicesDists,
1283 const size_t nFound =
1284 radiusSearchCustomCallback(query_point, resultSet, searchParams);
1295 template <
class SEARCH_CALLBACK>
1296 size_t radiusSearchCustomCallback(
1297 const ElementType *query_point, SEARCH_CALLBACK &resultSet,
1299 this->findNeighbors(resultSet, query_point, searchParams);
1300 return resultSet.size();
1310 BaseClassRef::m_size = dataset.kdtree_get_point_count();
1311 if (BaseClassRef::vind.size() != BaseClassRef::m_size)
1312 BaseClassRef::vind.resize(BaseClassRef::m_size);
1313 for (
size_t i = 0; i < BaseClassRef::m_size; i++)
1314 BaseClassRef::vind[i] = i;
1317 void computeBoundingBox(BoundingBox &bbox) {
1318 resize(bbox, (DIM > 0 ? DIM : BaseClassRef::dim));
1319 if (dataset.kdtree_get_bbox(bbox)) {
1322 const size_t N = dataset.kdtree_get_point_count();
1324 throw std::runtime_error(
"[nanoflann] computeBoundingBox() called but " 1325 "no data points found.");
1326 for (
int i = 0; i < (DIM > 0 ? DIM : BaseClassRef::dim); ++i) {
1327 bbox[i].low = bbox[i].high = this->dataset_get(*
this, 0, i);
1329 for (
size_t k = 1; k < N; ++k) {
1330 for (
int i = 0; i < (DIM > 0 ? DIM : BaseClassRef::dim); ++i) {
1331 if (this->dataset_get(*
this, k, i) < bbox[i].low)
1332 bbox[i].low = this->dataset_get(*
this, k, i);
1333 if (this->dataset_get(*
this, k, i) > bbox[i].high)
1334 bbox[i].high = this->dataset_get(*
this, k, i);
1346 template <
class RESULTSET>
1347 bool searchLevel(RESULTSET &result_set,
const ElementType *vec,
1348 const NodePtr node, DistanceType mindistsq,
1349 distance_vector_t &dists,
const float epsError)
const {
1351 if ((node->child1 ==
NULL) && (node->child2 ==
NULL)) {
1354 DistanceType worst_dist = result_set.worstDist();
1355 for (IndexType i = node->node_type.lr.left; i < node->node_type.lr.right;
1357 const IndexType index = BaseClassRef::vind[i];
1358 DistanceType dist = distance.evalMetric(
1359 vec, index, (DIM > 0 ? DIM : BaseClassRef::dim));
1360 if (dist < worst_dist) {
1361 if (!result_set.addPoint(dist, BaseClassRef::vind[i])) {
1372 int idx = node->node_type.sub.divfeat;
1373 ElementType val = vec[idx];
1374 DistanceType diff1 = val - node->node_type.sub.divlow;
1375 DistanceType diff2 = val - node->node_type.sub.divhigh;
1379 DistanceType cut_dist;
1380 if ((diff1 + diff2) < 0) {
1381 bestChild = node->child1;
1382 otherChild = node->child2;
1383 cut_dist = distance.accum_dist(val, node->node_type.sub.divhigh, idx);
1385 bestChild = node->child2;
1386 otherChild = node->child1;
1387 cut_dist = distance.accum_dist(val, node->node_type.sub.divlow, idx);
1391 if (!searchLevel(result_set, vec, bestChild, mindistsq, dists, epsError)) {
1397 DistanceType dst = dists[idx];
1398 mindistsq = mindistsq + cut_dist - dst;
1399 dists[idx] = cut_dist;
1400 if (mindistsq * epsError <= result_set.worstDist()) {
1401 if (!searchLevel(result_set, vec, otherChild, mindistsq, dists,
1418 void saveIndex(FILE *stream) { this->saveIndex_(*
this, stream); }
1425 void loadIndex(FILE *stream) { this->loadIndex_(*
this, stream); }
1465 template <
typename Distance,
class DatasetAdaptor,
int DIM = -1,
1466 typename IndexType =
size_t>
1469 Distance, DatasetAdaptor, DIM, IndexType>,
1470 Distance, DatasetAdaptor, DIM, IndexType> {
1486 Distance, DatasetAdaptor, DIM, IndexType>
1519 const int dimensionality,
const DatasetAdaptor &inputData,
1520 std::vector<int> &treeIndex_,
1523 : dataset(inputData), index_params(params), treeIndex(treeIndex_),
1524 distance(inputData) {
1525 BaseClassRef::root_node =
NULL;
1526 BaseClassRef::m_size = 0;
1527 BaseClassRef::m_size_at_index_build = 0;
1528 BaseClassRef::dim = dimensionality;
1530 BaseClassRef::dim = DIM;
1531 BaseClassRef::m_leaf_max_size = params.leaf_max_size;
1538 std::swap(BaseClassRef::vind, tmp.BaseClassRef::vind);
1539 std::swap(BaseClassRef::m_leaf_max_size, tmp.BaseClassRef::m_leaf_max_size);
1542 std::swap(BaseClassRef::m_size, tmp.BaseClassRef::m_size);
1543 std::swap(BaseClassRef::m_size_at_index_build,
1544 tmp.BaseClassRef::m_size_at_index_build);
1545 std::swap(BaseClassRef::root_node, tmp.BaseClassRef::root_node);
1546 std::swap(BaseClassRef::root_bbox, tmp.BaseClassRef::root_bbox);
1547 std::swap(BaseClassRef::pool, tmp.BaseClassRef::pool);
1555 BaseClassRef::m_size = BaseClassRef::vind.size();
1556 this->freeIndex(*
this);
1557 BaseClassRef::m_size_at_index_build = BaseClassRef::m_size;
1558 if (BaseClassRef::m_size == 0)
1560 computeBoundingBox(BaseClassRef::root_bbox);
1561 BaseClassRef::root_node =
1562 this->divideTree(*
this, 0, BaseClassRef::m_size,
1563 BaseClassRef::root_bbox);
1582 template <
typename RESULTSET>
1586 if (this->size(*
this) == 0)
1588 if (!BaseClassRef::root_node)
1590 float epsError = 1 + searchParams.
eps;
1593 distance_vector_t dists;
1595 assign(dists, (DIM > 0 ? DIM : BaseClassRef::dim),
1596 static_cast<typename distance_vector_t::value_type>(0));
1597 DistanceType distsq = this->computeInitialDistances(*
this, vec, dists);
1598 searchLevel(result, vec, BaseClassRef::root_node, distsq, dists,
1601 return result.full();
1613 size_t knnSearch(
const ElementType *query_point,
const size_t num_closest,
1614 IndexType *out_indices, DistanceType *out_distances_sq,
1615 const int = 10)
const {
1617 resultSet.
init(out_indices, out_distances_sq);
1619 return resultSet.
size();
1640 std::vector<std::pair<IndexType, DistanceType>> &IndicesDists,
1643 const size_t nFound =
1644 radiusSearchCustomCallback(query_point, resultSet, searchParams);
1655 template <
class SEARCH_CALLBACK>
1657 const ElementType *query_point, SEARCH_CALLBACK &resultSet,
1659 this->findNeighbors(resultSet, query_point, searchParams);
1660 return resultSet.size();
1667 resize(bbox, (DIM > 0 ? DIM : BaseClassRef::dim));
1669 if (dataset.kdtree_get_bbox(bbox)) {
1672 const size_t N = BaseClassRef::m_size;
1674 throw std::runtime_error(
"[nanoflann] computeBoundingBox() called but " 1675 "no data points found.");
1676 for (
int i = 0; i < (DIM > 0 ? DIM : BaseClassRef::dim); ++i) {
1677 bbox[i].low = bbox[i].high =
1678 this->dataset_get(*
this, BaseClassRef::vind[0], i);
1680 for (
size_t k = 1; k < N; ++k) {
1681 for (
int i = 0; i < (DIM > 0 ? DIM : BaseClassRef::dim); ++i) {
1682 if (this->dataset_get(*
this, BaseClassRef::vind[k], i) < bbox[i].low)
1683 bbox[i].low = this->dataset_get(*
this, BaseClassRef::vind[k], i);
1684 if (this->dataset_get(*
this, BaseClassRef::vind[k], i) > bbox[i].high)
1685 bbox[i].high = this->dataset_get(*
this, BaseClassRef::vind[k], i);
1695 template <
class RESULTSET>
1697 const NodePtr node, DistanceType mindistsq,
1698 distance_vector_t &dists,
const float epsError)
const {
1703 DistanceType worst_dist = result_set.worstDist();
1704 for (IndexType i = node->
node_type.
lr.left; i < node->node_type.lr.right;
1706 const IndexType index = BaseClassRef::vind[i];
1707 if (treeIndex[index] == -1)
1709 DistanceType dist = distance.evalMetric(
1710 vec, index, (DIM > 0 ? DIM : BaseClassRef::dim));
1711 if (dist < worst_dist) {
1712 if (!result_set.addPoint(
1713 static_cast<typename RESULTSET::DistanceType>(dist),
1714 static_cast<typename RESULTSET::IndexType>(
1715 BaseClassRef::vind[i]))) {
1727 ElementType val = vec[idx];
1729 DistanceType diff2 = val - node->
node_type.
sub.divhigh;
1733 DistanceType cut_dist;
1734 if ((diff1 + diff2) < 0) {
1735 bestChild = node->
child1;
1736 otherChild = node->
child2;
1737 cut_dist = distance.accum_dist(val, node->
node_type.
sub.divhigh, idx);
1739 bestChild = node->
child2;
1740 otherChild = node->
child1;
1741 cut_dist = distance.accum_dist(val, node->
node_type.
sub.divlow, idx);
1745 searchLevel(result_set, vec, bestChild, mindistsq, dists, epsError);
1747 DistanceType dst = dists[idx];
1748 mindistsq = mindistsq + cut_dist - dst;
1749 dists[idx] = cut_dist;
1750 if (mindistsq * epsError <= result_set.worstDist()) {
1751 searchLevel(result_set, vec, otherChild, mindistsq, dists, epsError);
1762 void saveIndex(FILE *stream) { this->saveIndex_(*
this, stream); }
1769 void loadIndex(FILE *stream) { this->loadIndex_(*
this, stream); }
1786 template <
typename Distance,
class DatasetAdaptor,
int DIM = -1,
1787 typename IndexType =
size_t>
1835 std::vector<my_kd_tree_t> index_(
1836 treeCount, my_kd_tree_t(dim , dataset, treeIndex, index_params));
1858 const DatasetAdaptor &inputData,
1861 const size_t maximumPointCount = 1000000000U)
1862 : dataset(inputData), index_params(params), distance(inputData) {
1863 treeCount =
static_cast<size_t>(std::log2(maximumPointCount));
1865 dim = dimensionality;
1871 const size_t num_initial_points = dataset.kdtree_get_point_count();
1872 if (num_initial_points > 0) {
1873 addPoints(0, num_initial_points - 1);
1880 IndexType> &) =
delete;
1884 size_t count = end - start + 1;
1885 treeIndex.resize(treeIndex.size() + count);
1886 for (IndexType idx = start; idx <= end; idx++) {
1887 int pos = First0Bit(pointCount);
1888 index[pos].vind.clear();
1889 treeIndex[pointCount] = pos;
1890 for (
int i = 0; i < pos; i++) {
1891 for (
int j = 0; j < static_cast<int>(index[i].vind.size()); j++) {
1892 index[pos].vind.push_back(index[i].vind[j]);
1893 if (treeIndex[index[i].vind[j]] != -1)
1894 treeIndex[index[i].vind[j]] = pos;
1896 index[i].vind.clear();
1897 index[i].freeIndex(index[i]);
1899 index[pos].vind.push_back(idx);
1900 index[pos].buildIndex();
1907 if (idx >= pointCount)
1909 treeIndex[idx] = -1;
1925 template <
typename RESULTSET>
1928 for (
size_t i = 0; i < treeCount; i++) {
1929 index[i].findNeighbors(result, &vec[0], searchParams);
1931 return result.full();
1956 bool row_major =
true>
1959 typedef typename MatrixType::Scalar num_t;
1960 typedef typename MatrixType::Index IndexType;
1962 typename Distance::template traits<num_t, self_t>::distance_t metric_t;
1964 MatrixType::ColsAtCompileTime, IndexType>
1972 const std::reference_wrapper<const MatrixType> &mat,
1973 const int leaf_max_size = 10)
1974 : m_data_matrix(mat) {
1975 const auto dims = row_major ? mat.get().cols() : mat.get().rows();
1976 if (
size_t(dims) != dimensionality)
1977 throw std::runtime_error(
1978 "Error: 'dimensionality' must match column count in data matrix");
1979 if (DIM > 0 &&
int(dims) != DIM)
1980 throw std::runtime_error(
1981 "Data set dimensionality does not match the 'DIM' template argument");
1983 new index_t(static_cast<int>(dims), *
this ,
1985 index->buildIndex();
1994 const std::reference_wrapper<const MatrixType> m_data_matrix;
2002 inline void query(
const num_t *query_point,
const size_t num_closest,
2003 IndexType *out_indices, num_t *out_distances_sq,
2004 const int = 10)
const {
2006 resultSet.
init(out_indices, out_distances_sq);
2013 const self_t &derived()
const {
return *
this; }
2014 self_t &derived() {
return *
this; }
2017 inline size_t kdtree_get_point_count()
const {
2019 return m_data_matrix.get().rows();
2021 return m_data_matrix.get().cols();
2025 inline num_t kdtree_get_pt(
const IndexType idx,
size_t dim)
const {
2027 return m_data_matrix.get().coeff(idx, IndexType(dim));
2029 return m_data_matrix.get().coeff(IndexType(dim), idx);
2037 template <
class BBOX>
bool kdtree_get_bbox(BBOX & )
const {
int First0Bit(IndexType num)
size_t veclen(const Derived &obj)
void computeBoundingBox(BoundingBox &bbox)
std::vector< int > & treeIndex
L2_Simple_Adaptor< T, DataSource > distance_L2_Simple
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
void middleSplit_(Derived &obj, IndexType *ind, IndexType count, IndexType &index, int &cutfeat, DistanceType &cutval, const BoundingBox &bbox)
SO3_Adaptor< T, DataSource > distance_t
void init(const M_string &remappings)
BaseClassRef::DistanceType DistanceType
BaseClassRef::BoundingBox BoundingBox
KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, DIM > index_container_t
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)
DistanceType accum_dist(const U a, const V b, int dim) const
SO2_Adaptor(const DataSource &_data_source)
const DatasetAdaptor & dataset
The source of our data.
size_t size(const Derived &obj) const
const DatasetAdaptor & dataset
The source of our data.
void load_value(FILE *stream, T &value, size_t count=1)
size_t m_size_at_index_build
KDTreeSingleIndexAdaptorParams index_params
int divfeat
Dimension used for subdivision.
SO2_Adaptor< T, DataSource > distance_t
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)
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
Distance::ElementType ElementType
void loadIndex_(Derived &obj, FILE *stream)
std::array< T, DIM > container_t
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.
Distance::DistanceType DistanceType
std::vector< T > container_t
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.
const DataSource & data_source
T * allocate(size_t count=1)
KDTreeSingleIndexDynamicAdaptor_ operator=(const KDTreeSingleIndexDynamicAdaptor_ &rhs)
void saveIndex(FILE *stream)
void init(IndexType *indices_, DistanceType *dists_)
BaseClassRef::distance_vector_t distance_vector_t
NodePtr divideTree(Derived &obj, const IndexType left, const IndexType right, BoundingBox &bbox)
void saveIndex_(Derived &obj, FILE *stream)
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
void planeSplit(Derived &obj, IndexType *ind, const IndexType count, int cutfeat, DistanceType &cutval, IndexType &lim1, IndexType &lim2)
KDTreeSingleIndexDynamicAdaptor(const int dimensionality, const DatasetAdaptor &inputData, const KDTreeSingleIndexAdaptorParams ¶ms=KDTreeSingleIndexAdaptorParams(), const size_t maximumPointCount=1000000000U)
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 findNeighbors(RESULTSET &result, const ElementType *vec, const SearchParams &searchParams) const
struct nanoflann::KDTreeBaseClass::Node::@0::nonleaf sub
std::vector< index_container_t > index
nanoflann::KDTreeBaseClass< nanoflann::KDTreeSingleIndexDynamicAdaptor_< Distance, DatasetAdaptor, DIM, IndexType >, Distance, DatasetAdaptor, DIM, IndexType > BaseClassRef
void removePoint(size_t idx)
KDTreeSingleIndexDynamicAdaptor_(const int dimensionality, const DatasetAdaptor &inputData, std::vector< int > &treeIndex_, const KDTreeSingleIndexAdaptorParams ¶ms=KDTreeSingleIndexAdaptorParams())
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)
void save_value(FILE *stream, const T &value, size_t count=1)
_DistanceType DistanceType
array_or_vector_selector< DIM, Interval >::container_t BoundingBox
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)
_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 findNeighbors(RESULTSET &result, const ElementType *vec, const SearchParams &searchParams) const
std::vector< IndexType > vind
union nanoflann::KDTreeBaseClass::Node::@0 node_type
std::enable_if< has_assign< Container >::value, void >::type assign(Container &c, const size_t nElements, const T &value)