nanoflann_impl.hpp 72 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547154815491550155115521553155415551556155715581559156015611562156315641565156615671568156915701571157215731574157515761577157815791580158115821583158415851586158715881589159015911592159315941595159615971598159916001601160216031604160516061607160816091610161116121613161416151616161716181619162016211622162316241625162616271628162916301631163216331634163516361637163816391640164116421643164416451646164716481649165016511652165316541655165616571658165916601661166216631664166516661667166816691670167116721673167416751676167716781679168016811682168316841685168616871688168916901691169216931694169516961697169816991700170117021703170417051706170717081709171017111712171317141715171617171718171917201721172217231724172517261727172817291730173117321733173417351736173717381739174017411742174317441745174617471748174917501751175217531754175517561757175817591760176117621763176417651766176717681769177017711772177317741775177617771778177917801781178217831784178517861787178817891790179117921793179417951796179717981799180018011802180318041805180618071808180918101811181218131814181518161817181818191820182118221823182418251826182718281829183018311832183318341835183618371838183918401841184218431844184518461847184818491850185118521853185418551856185718581859186018611862186318641865186618671868186918701871187218731874187518761877187818791880188118821883188418851886188718881889189018911892189318941895189618971898189919001901190219031904190519061907190819091910191119121913191419151916191719181919192019211922192319241925192619271928192919301931193219331934193519361937193819391940194119421943194419451946194719481949195019511952195319541955195619571958195919601961196219631964196519661967196819691970197119721973197419751976197719781979198019811982198319841985198619871988198919901991199219931994199519961997199819992000200120022003200420052006200720082009201020112012201320142015201620172018201920202021202220232024202520262027202820292030203120322033203420352036203720382039204020412042204320442045204620472048204920502051205220532054205520562057
  1. /************************************************************
  2. *
  3. * Copyright (c) 2021, University of California, Los Angeles
  4. *
  5. * Authors: Kenny J. Chen, Brett T. Lopez
  6. * Contact: kennyjchen@ucla.edu, btlopez@ucla.edu
  7. *
  8. ***********************************************************/
  9. /***********************************************************************
  10. * Software License Agreement (BSD License)
  11. *
  12. * Copyright 2008-2009 Marius Muja (mariusm@cs.ubc.ca). All rights reserved.
  13. * Copyright 2008-2009 David G. Lowe (lowe@cs.ubc.ca). All rights reserved.
  14. * Copyright 2011-2021 Jose Luis Blanco (joseluisblancoc@gmail.com).
  15. * All rights reserved.
  16. *
  17. * THE BSD LICENSE
  18. *
  19. * Redistribution and use in source and binary forms, with or without
  20. * modification, are permitted provided that the following conditions
  21. * are met:
  22. *
  23. * 1. Redistributions of source code must retain the above copyright
  24. * notice, this list of conditions and the following disclaimer.
  25. * 2. Redistributions in binary form must reproduce the above copyright
  26. * notice, this list of conditions and the following disclaimer in the
  27. * documentation and/or other materials provided with the distribution.
  28. *
  29. * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
  30. * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
  31. * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
  32. * IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT,
  33. * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
  34. * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
  35. * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
  36. * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
  37. * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
  38. * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
  39. *************************************************************************/
  40. /** \mainpage nanoflann C++ API documentation
  41. * nanoflann is a C++ header-only library for building KD-Trees, mostly
  42. * optimized for 2D or 3D point clouds.
  43. *
  44. * nanoflann does not require compiling or installing, just an
  45. * #include <nanoflann.hpp> in your code.
  46. *
  47. * See:
  48. * - <a href="modules.html" >C++ API organized by modules</a>
  49. * - <a href="https://github.com/jlblancoc/nanoflann" >Online README</a>
  50. * - <a href="http://jlblancoc.github.io/nanoflann/" >Doxygen
  51. * documentation</a>
  52. */
  53. #ifndef NANOFLANN_HPP_
  54. #define NANOFLANN_HPP_
  55. #include <algorithm>
  56. #include <array>
  57. #include <cassert>
  58. #include <cmath> // for abs()
  59. #include <cstdio> // for fwrite()
  60. #include <cstdlib> // for abs()
  61. #include <functional>
  62. #include <limits> // std::reference_wrapper
  63. #include <stdexcept>
  64. #include <vector>
  65. /** Library version: 0xMmP (M=Major,m=minor,P=patch) */
  66. #define NANOFLANN_VERSION 0x132
  67. // Avoid conflicting declaration of min/max macros in windows headers
  68. #if !defined(NOMINMAX) && \
  69. (defined(_WIN32) || defined(_WIN32_) || defined(WIN32) || defined(_WIN64))
  70. #define NOMINMAX
  71. #ifdef max
  72. #undef max
  73. #undef min
  74. #endif
  75. #endif
  76. namespace nanoflann {
  77. /** @addtogroup nanoflann_grp nanoflann C++ library for ANN
  78. * @{ */
  79. /** the PI constant (required to avoid MSVC missing symbols) */
  80. template <typename T> T pi_const() {
  81. return static_cast<T>(3.14159265358979323846);
  82. }
  83. /**
  84. * Traits if object is resizable and assignable (typically has a resize | assign
  85. * method)
  86. */
  87. template <typename T, typename = int> struct has_resize : std::false_type {};
  88. template <typename T>
  89. struct has_resize<T, decltype((void)std::declval<T>().resize(1), 0)>
  90. : std::true_type {};
  91. template <typename T, typename = int> struct has_assign : std::false_type {};
  92. template <typename T>
  93. struct has_assign<T, decltype((void)std::declval<T>().assign(1, 0), 0)>
  94. : std::true_type {};
  95. /**
  96. * Free function to resize a resizable object
  97. */
  98. template <typename Container>
  99. inline typename std::enable_if<has_resize<Container>::value, void>::type
  100. resize(Container &c, const size_t nElements) {
  101. c.resize(nElements);
  102. }
  103. /**
  104. * Free function that has no effects on non resizable containers (e.g.
  105. * std::array) It raises an exception if the expected size does not match
  106. */
  107. template <typename Container>
  108. inline typename std::enable_if<!has_resize<Container>::value, void>::type
  109. resize(Container &c, const size_t nElements) {
  110. if (nElements != c.size())
  111. throw std::logic_error("Try to change the size of a std::array.");
  112. }
  113. /**
  114. * Free function to assign to a container
  115. */
  116. template <typename Container, typename T>
  117. inline typename std::enable_if<has_assign<Container>::value, void>::type
  118. assign(Container &c, const size_t nElements, const T &value) {
  119. c.assign(nElements, value);
  120. }
  121. /**
  122. * Free function to assign to a std::array
  123. */
  124. template <typename Container, typename T>
  125. inline typename std::enable_if<!has_assign<Container>::value, void>::type
  126. assign(Container &c, const size_t nElements, const T &value) {
  127. for (size_t i = 0; i < nElements; i++)
  128. c[i] = value;
  129. }
  130. /** @addtogroup result_sets_grp Result set classes
  131. * @{ */
  132. template <typename _DistanceType, typename _IndexType = size_t,
  133. typename _CountType = size_t>
  134. class KNNResultSet {
  135. public:
  136. typedef _DistanceType DistanceType;
  137. typedef _IndexType IndexType;
  138. typedef _CountType CountType;
  139. private:
  140. IndexType *indices;
  141. DistanceType *dists;
  142. CountType capacity;
  143. CountType count;
  144. public:
  145. inline KNNResultSet(CountType capacity_)
  146. : indices(0), dists(0), capacity(capacity_), count(0) {}
  147. inline void init(IndexType *indices_, DistanceType *dists_) {
  148. indices = indices_;
  149. dists = dists_;
  150. count = 0;
  151. if (capacity)
  152. dists[capacity - 1] = (std::numeric_limits<DistanceType>::max)();
  153. }
  154. inline CountType size() const { return count; }
  155. inline bool full() const { return count == capacity; }
  156. /**
  157. * Called during search to add an element matching the criteria.
  158. * @return true if the search should be continued, false if the results are
  159. * sufficient
  160. */
  161. inline bool addPoint(DistanceType dist, IndexType index) {
  162. CountType i;
  163. for (i = count; i > 0; --i) {
  164. #ifdef NANOFLANN_FIRST_MATCH // If defined and two points have the same
  165. // distance, the one with the lowest-index will be
  166. // returned first.
  167. if ((dists[i - 1] > dist) ||
  168. ((dist == dists[i - 1]) && (indices[i - 1] > index))) {
  169. #else
  170. if (dists[i - 1] > dist) {
  171. #endif
  172. if (i < capacity) {
  173. dists[i] = dists[i - 1];
  174. indices[i] = indices[i - 1];
  175. }
  176. } else
  177. break;
  178. }
  179. if (i < capacity) {
  180. dists[i] = dist;
  181. indices[i] = index;
  182. }
  183. if (count < capacity)
  184. count++;
  185. // tell caller that the search shall continue
  186. return true;
  187. }
  188. inline DistanceType worstDist() const { return dists[capacity - 1]; }
  189. };
  190. /** operator "<" for std::sort() */
  191. struct IndexDist_Sorter {
  192. /** PairType will be typically: std::pair<IndexType,DistanceType> */
  193. template <typename PairType>
  194. inline bool operator()(const PairType &p1, const PairType &p2) const {
  195. return p1.second < p2.second;
  196. }
  197. };
  198. /**
  199. * A result-set class used when performing a radius based search.
  200. */
  201. template <typename _DistanceType, typename _IndexType = size_t>
  202. class RadiusResultSet {
  203. public:
  204. typedef _DistanceType DistanceType;
  205. typedef _IndexType IndexType;
  206. public:
  207. const DistanceType radius;
  208. std::vector<std::pair<IndexType, DistanceType>> &m_indices_dists;
  209. inline RadiusResultSet(
  210. DistanceType radius_,
  211. std::vector<std::pair<IndexType, DistanceType>> &indices_dists)
  212. : radius(radius_), m_indices_dists(indices_dists) {
  213. init();
  214. }
  215. inline void init() { clear(); }
  216. inline void clear() { m_indices_dists.clear(); }
  217. inline size_t size() const { return m_indices_dists.size(); }
  218. inline bool full() const { return true; }
  219. /**
  220. * Called during search to add an element matching the criteria.
  221. * @return true if the search should be continued, false if the results are
  222. * sufficient
  223. */
  224. inline bool addPoint(DistanceType dist, IndexType index) {
  225. if (dist < radius)
  226. m_indices_dists.push_back(std::make_pair(index, dist));
  227. return true;
  228. }
  229. inline DistanceType worstDist() const { return radius; }
  230. /**
  231. * Find the worst result (furtherest neighbor) without copying or sorting
  232. * Pre-conditions: size() > 0
  233. */
  234. std::pair<IndexType, DistanceType> worst_item() const {
  235. if (m_indices_dists.empty())
  236. throw std::runtime_error("Cannot invoke RadiusResultSet::worst_item() on "
  237. "an empty list of results.");
  238. typedef
  239. typename std::vector<std::pair<IndexType, DistanceType>>::const_iterator
  240. DistIt;
  241. DistIt it = std::max_element(m_indices_dists.begin(), m_indices_dists.end(),
  242. IndexDist_Sorter());
  243. return *it;
  244. }
  245. };
  246. /** @} */
  247. /** @addtogroup loadsave_grp Load/save auxiliary functions
  248. * @{ */
  249. template <typename T>
  250. void save_value(FILE *stream, const T &value, size_t count = 1) {
  251. fwrite(&value, sizeof(value), count, stream);
  252. }
  253. template <typename T>
  254. void save_value(FILE *stream, const std::vector<T> &value) {
  255. size_t size = value.size();
  256. fwrite(&size, sizeof(size_t), 1, stream);
  257. fwrite(&value[0], sizeof(T), size, stream);
  258. }
  259. template <typename T>
  260. void load_value(FILE *stream, T &value, size_t count = 1) {
  261. size_t read_cnt = fread(&value, sizeof(value), count, stream);
  262. if (read_cnt != count) {
  263. throw std::runtime_error("Cannot read from file");
  264. }
  265. }
  266. template <typename T> void load_value(FILE *stream, std::vector<T> &value) {
  267. size_t size;
  268. size_t read_cnt = fread(&size, sizeof(size_t), 1, stream);
  269. if (read_cnt != 1) {
  270. throw std::runtime_error("Cannot read from file");
  271. }
  272. value.resize(size);
  273. read_cnt = fread(&value[0], sizeof(T), size, stream);
  274. if (read_cnt != size) {
  275. throw std::runtime_error("Cannot read from file");
  276. }
  277. }
  278. /** @} */
  279. /** @addtogroup metric_grp Metric (distance) classes
  280. * @{ */
  281. struct Metric {};
  282. /** Manhattan distance functor (generic version, optimized for
  283. * high-dimensionality data sets). Corresponding distance traits:
  284. * nanoflann::metric_L1 \tparam T Type of the elements (e.g. double, float,
  285. * uint8_t) \tparam _DistanceType Type of distance variables (must be signed)
  286. * (e.g. float, double, int64_t)
  287. */
  288. template <class T, class DataSource, typename _DistanceType = T>
  289. struct L1_Adaptor {
  290. typedef T ElementType;
  291. typedef _DistanceType DistanceType;
  292. const DataSource &data_source;
  293. L1_Adaptor(const DataSource &_data_source) : data_source(_data_source) {}
  294. inline DistanceType evalMetric(const T *a, const size_t b_idx, size_t size,
  295. DistanceType worst_dist = -1) const {
  296. DistanceType result = DistanceType();
  297. const T *last = a + size;
  298. const T *lastgroup = last - 3;
  299. size_t d = 0;
  300. /* Process 4 items with each loop for efficiency. */
  301. while (a < lastgroup) {
  302. const DistanceType diff0 =
  303. std::abs(a[0] - data_source.kdtree_get_pt(b_idx, d++));
  304. const DistanceType diff1 =
  305. std::abs(a[1] - data_source.kdtree_get_pt(b_idx, d++));
  306. const DistanceType diff2 =
  307. std::abs(a[2] - data_source.kdtree_get_pt(b_idx, d++));
  308. const DistanceType diff3 =
  309. std::abs(a[3] - data_source.kdtree_get_pt(b_idx, d++));
  310. result += diff0 + diff1 + diff2 + diff3;
  311. a += 4;
  312. if ((worst_dist > 0) && (result > worst_dist)) {
  313. return result;
  314. }
  315. }
  316. /* Process last 0-3 components. Not needed for standard vector lengths. */
  317. while (a < last) {
  318. result += std::abs(*a++ - data_source.kdtree_get_pt(b_idx, d++));
  319. }
  320. return result;
  321. }
  322. template <typename U, typename V>
  323. inline DistanceType accum_dist(const U a, const V b, const size_t) const {
  324. return std::abs(a - b);
  325. }
  326. };
  327. /** Squared Euclidean distance functor (generic version, optimized for
  328. * high-dimensionality data sets). Corresponding distance traits:
  329. * nanoflann::metric_L2 \tparam T Type of the elements (e.g. double, float,
  330. * uint8_t) \tparam _DistanceType Type of distance variables (must be signed)
  331. * (e.g. float, double, int64_t)
  332. */
  333. template <class T, class DataSource, typename _DistanceType = T>
  334. struct L2_Adaptor {
  335. typedef T ElementType;
  336. typedef _DistanceType DistanceType;
  337. const DataSource &data_source;
  338. L2_Adaptor(const DataSource &_data_source) : data_source(_data_source) {}
  339. inline DistanceType evalMetric(const T *a, const size_t b_idx, size_t size,
  340. DistanceType worst_dist = -1) const {
  341. DistanceType result = DistanceType();
  342. const T *last = a + size;
  343. const T *lastgroup = last - 3;
  344. size_t d = 0;
  345. /* Process 4 items with each loop for efficiency. */
  346. while (a < lastgroup) {
  347. const DistanceType diff0 = a[0] - data_source.kdtree_get_pt(b_idx, d++);
  348. const DistanceType diff1 = a[1] - data_source.kdtree_get_pt(b_idx, d++);
  349. const DistanceType diff2 = a[2] - data_source.kdtree_get_pt(b_idx, d++);
  350. const DistanceType diff3 = a[3] - data_source.kdtree_get_pt(b_idx, d++);
  351. result += diff0 * diff0 + diff1 * diff1 + diff2 * diff2 + diff3 * diff3;
  352. a += 4;
  353. if ((worst_dist > 0) && (result > worst_dist)) {
  354. return result;
  355. }
  356. }
  357. /* Process last 0-3 components. Not needed for standard vector lengths. */
  358. while (a < last) {
  359. const DistanceType diff0 = *a++ - data_source.kdtree_get_pt(b_idx, d++);
  360. result += diff0 * diff0;
  361. }
  362. return result;
  363. }
  364. template <typename U, typename V>
  365. inline DistanceType accum_dist(const U a, const V b, const size_t) const {
  366. return (a - b) * (a - b);
  367. }
  368. };
  369. /** Squared Euclidean (L2) distance functor (suitable for low-dimensionality
  370. * datasets, like 2D or 3D point clouds) Corresponding distance traits:
  371. * nanoflann::metric_L2_Simple \tparam T Type of the elements (e.g. double,
  372. * float, uint8_t) \tparam _DistanceType Type of distance variables (must be
  373. * signed) (e.g. float, double, int64_t)
  374. */
  375. template <class T, class DataSource, typename _DistanceType = T>
  376. struct L2_Simple_Adaptor {
  377. typedef T ElementType;
  378. typedef _DistanceType DistanceType;
  379. const DataSource &data_source;
  380. L2_Simple_Adaptor(const DataSource &_data_source)
  381. : data_source(_data_source) {}
  382. inline DistanceType evalMetric(const T *a, const size_t b_idx,
  383. size_t size) const {
  384. DistanceType result = DistanceType();
  385. for (size_t i = 0; i < size; ++i) {
  386. const DistanceType diff = a[i] - data_source.kdtree_get_pt(b_idx, i);
  387. result += diff * diff;
  388. }
  389. return result;
  390. }
  391. template <typename U, typename V>
  392. inline DistanceType accum_dist(const U a, const V b, const size_t) const {
  393. return (a - b) * (a - b);
  394. }
  395. };
  396. /** SO2 distance functor
  397. * Corresponding distance traits: nanoflann::metric_SO2
  398. * \tparam T Type of the elements (e.g. double, float)
  399. * \tparam _DistanceType Type of distance variables (must be signed) (e.g.
  400. * float, double) orientation is constrained to be in [-pi, pi]
  401. */
  402. template <class T, class DataSource, typename _DistanceType = T>
  403. struct SO2_Adaptor {
  404. typedef T ElementType;
  405. typedef _DistanceType DistanceType;
  406. const DataSource &data_source;
  407. SO2_Adaptor(const DataSource &_data_source) : data_source(_data_source) {}
  408. inline DistanceType evalMetric(const T *a, const size_t b_idx,
  409. size_t size) const {
  410. return accum_dist(a[size - 1], data_source.kdtree_get_pt(b_idx, size - 1),
  411. size - 1);
  412. }
  413. /** Note: this assumes that input angles are already in the range [-pi,pi] */
  414. template <typename U, typename V>
  415. inline DistanceType accum_dist(const U a, const V b, const size_t) const {
  416. DistanceType result = DistanceType();
  417. DistanceType PI = pi_const<DistanceType>();
  418. result = b - a;
  419. if (result > PI)
  420. result -= 2 * PI;
  421. else if (result < -PI)
  422. result += 2 * PI;
  423. return result;
  424. }
  425. };
  426. /** SO3 distance functor (Uses L2_Simple)
  427. * Corresponding distance traits: nanoflann::metric_SO3
  428. * \tparam T Type of the elements (e.g. double, float)
  429. * \tparam _DistanceType Type of distance variables (must be signed) (e.g.
  430. * float, double)
  431. */
  432. template <class T, class DataSource, typename _DistanceType = T>
  433. struct SO3_Adaptor {
  434. typedef T ElementType;
  435. typedef _DistanceType DistanceType;
  436. L2_Simple_Adaptor<T, DataSource> distance_L2_Simple;
  437. SO3_Adaptor(const DataSource &_data_source)
  438. : distance_L2_Simple(_data_source) {}
  439. inline DistanceType evalMetric(const T *a, const size_t b_idx,
  440. size_t size) const {
  441. return distance_L2_Simple.evalMetric(a, b_idx, size);
  442. }
  443. template <typename U, typename V>
  444. inline DistanceType accum_dist(const U a, const V b, const size_t idx) const {
  445. return distance_L2_Simple.accum_dist(a, b, idx);
  446. }
  447. };
  448. /** Metaprogramming helper traits class for the L1 (Manhattan) metric */
  449. struct metric_L1 : public Metric {
  450. template <class T, class DataSource> struct traits {
  451. typedef L1_Adaptor<T, DataSource> distance_t;
  452. };
  453. };
  454. /** Metaprogramming helper traits class for the L2 (Euclidean) metric */
  455. struct metric_L2 : public Metric {
  456. template <class T, class DataSource> struct traits {
  457. typedef L2_Adaptor<T, DataSource> distance_t;
  458. };
  459. };
  460. /** Metaprogramming helper traits class for the L2_simple (Euclidean) metric */
  461. struct metric_L2_Simple : public Metric {
  462. template <class T, class DataSource> struct traits {
  463. typedef L2_Simple_Adaptor<T, DataSource> distance_t;
  464. };
  465. };
  466. /** Metaprogramming helper traits class for the SO3_InnerProdQuat metric */
  467. struct metric_SO2 : public Metric {
  468. template <class T, class DataSource> struct traits {
  469. typedef SO2_Adaptor<T, DataSource> distance_t;
  470. };
  471. };
  472. /** Metaprogramming helper traits class for the SO3_InnerProdQuat metric */
  473. struct metric_SO3 : public Metric {
  474. template <class T, class DataSource> struct traits {
  475. typedef SO3_Adaptor<T, DataSource> distance_t;
  476. };
  477. };
  478. /** @} */
  479. /** @addtogroup param_grp Parameter structs
  480. * @{ */
  481. /** Parameters (see README.md) */
  482. struct KDTreeSingleIndexAdaptorParams {
  483. KDTreeSingleIndexAdaptorParams(size_t _leaf_max_size = 10)
  484. : leaf_max_size(_leaf_max_size) {}
  485. size_t leaf_max_size;
  486. };
  487. /** Search options for KDTreeSingleIndexAdaptor::findNeighbors() */
  488. struct SearchParams {
  489. /** Note: The first argument (checks_IGNORED_) is ignored, but kept for
  490. * compatibility with the FLANN interface */
  491. SearchParams(int checks_IGNORED_ = 32, float eps_ = 0, bool sorted_ = true)
  492. : checks(checks_IGNORED_), eps(eps_), sorted(sorted_) {}
  493. int checks; //!< Ignored parameter (Kept for compatibility with the FLANN
  494. //!< interface).
  495. float eps; //!< search for eps-approximate neighbours (default: 0)
  496. bool sorted; //!< only for radius search, require neighbours sorted by
  497. //!< distance (default: true)
  498. };
  499. /** @} */
  500. /** @addtogroup memalloc_grp Memory allocation
  501. * @{ */
  502. /**
  503. * Allocates (using C's malloc) a generic type T.
  504. *
  505. * Params:
  506. * count = number of instances to allocate.
  507. * Returns: pointer (of type T*) to memory buffer
  508. */
  509. template <typename T> inline T *allocate(size_t count = 1) {
  510. T *mem = static_cast<T *>(::malloc(sizeof(T) * count));
  511. return mem;
  512. }
  513. /**
  514. * Pooled storage allocator
  515. *
  516. * The following routines allow for the efficient allocation of storage in
  517. * small chunks from a specified pool. Rather than allowing each structure
  518. * to be freed individually, an entire pool of storage is freed at once.
  519. * This method has two advantages over just using malloc() and free(). First,
  520. * it is far more efficient for allocating small objects, as there is
  521. * no overhead for remembering all the information needed to free each
  522. * object or consolidating fragmented memory. Second, the decision about
  523. * how long to keep an object is made at the time of allocation, and there
  524. * is no need to track down all the objects to free them.
  525. *
  526. */
  527. const size_t WORDSIZE = 16;
  528. const size_t BLOCKSIZE = 8192;
  529. class PooledAllocator {
  530. /* We maintain memory alignment to word boundaries by requiring that all
  531. allocations be in multiples of the machine wordsize. */
  532. /* Size of machine word in bytes. Must be power of 2. */
  533. /* Minimum number of bytes requested at a time from the system. Must be
  534. * multiple of WORDSIZE. */
  535. size_t remaining; /* Number of bytes left in current block of storage. */
  536. void *base; /* Pointer to base of current block of storage. */
  537. void *loc; /* Current location in block to next allocate memory. */
  538. void internal_init() {
  539. remaining = 0;
  540. base = NULL;
  541. usedMemory = 0;
  542. wastedMemory = 0;
  543. }
  544. public:
  545. size_t usedMemory;
  546. size_t wastedMemory;
  547. /**
  548. Default constructor. Initializes a new pool.
  549. */
  550. PooledAllocator() { internal_init(); }
  551. /**
  552. * Destructor. Frees all the memory allocated in this pool.
  553. */
  554. ~PooledAllocator() { free_all(); }
  555. /** Frees all allocated memory chunks */
  556. void free_all() {
  557. while (base != NULL) {
  558. void *prev =
  559. *(static_cast<void **>(base)); /* Get pointer to prev block. */
  560. ::free(base);
  561. base = prev;
  562. }
  563. internal_init();
  564. }
  565. /**
  566. * Returns a pointer to a piece of new memory of the given size in bytes
  567. * allocated from the pool.
  568. */
  569. void *malloc(const size_t req_size) {
  570. /* Round size up to a multiple of wordsize. The following expression
  571. only works for WORDSIZE that is a power of 2, by masking last bits of
  572. incremented size to zero.
  573. */
  574. const size_t size = (req_size + (WORDSIZE - 1)) & ~(WORDSIZE - 1);
  575. /* Check whether a new block must be allocated. Note that the first word
  576. of a block is reserved for a pointer to the previous block.
  577. */
  578. if (size > remaining) {
  579. wastedMemory += remaining;
  580. /* Allocate new storage. */
  581. const size_t blocksize =
  582. (size + sizeof(void *) + (WORDSIZE - 1) > BLOCKSIZE)
  583. ? size + sizeof(void *) + (WORDSIZE - 1)
  584. : BLOCKSIZE;
  585. // use the standard C malloc to allocate memory
  586. void *m = ::malloc(blocksize);
  587. if (!m) {
  588. fprintf(stderr, "Failed to allocate memory.\n");
  589. throw std::bad_alloc();
  590. }
  591. /* Fill first word of new block with pointer to previous block. */
  592. static_cast<void **>(m)[0] = base;
  593. base = m;
  594. size_t shift = 0;
  595. // int size_t = (WORDSIZE - ( (((size_t)m) + sizeof(void*)) &
  596. // (WORDSIZE-1))) & (WORDSIZE-1);
  597. remaining = blocksize - sizeof(void *) - shift;
  598. loc = (static_cast<char *>(m) + sizeof(void *) + shift);
  599. }
  600. void *rloc = loc;
  601. loc = static_cast<char *>(loc) + size;
  602. remaining -= size;
  603. usedMemory += size;
  604. return rloc;
  605. }
  606. /**
  607. * Allocates (using this pool) a generic type T.
  608. *
  609. * Params:
  610. * count = number of instances to allocate.
  611. * Returns: pointer (of type T*) to memory buffer
  612. */
  613. template <typename T> T *allocate(const size_t count = 1) {
  614. T *mem = static_cast<T *>(this->malloc(sizeof(T) * count));
  615. return mem;
  616. }
  617. };
  618. /** @} */
  619. /** @addtogroup nanoflann_metaprog_grp Auxiliary metaprogramming stuff
  620. * @{ */
  621. /** Used to declare fixed-size arrays when DIM>0, dynamically-allocated vectors
  622. * when DIM=-1. Fixed size version for a generic DIM:
  623. */
  624. template <int DIM, typename T> struct array_or_vector_selector {
  625. typedef std::array<T, DIM> container_t;
  626. };
  627. /** Dynamic size version */
  628. template <typename T> struct array_or_vector_selector<-1, T> {
  629. typedef std::vector<T> container_t;
  630. };
  631. /** @} */
  632. /** kd-tree base-class
  633. *
  634. * Contains the member functions common to the classes KDTreeSingleIndexAdaptor
  635. * and KDTreeSingleIndexDynamicAdaptor_.
  636. *
  637. * \tparam Derived The name of the class which inherits this class.
  638. * \tparam DatasetAdaptor The user-provided adaptor (see comments above).
  639. * \tparam Distance The distance metric to use, these are all classes derived
  640. * from nanoflann::Metric \tparam DIM Dimensionality of data points (e.g. 3 for
  641. * 3D points) \tparam IndexType Will be typically size_t or int
  642. */
  643. template <class Derived, typename Distance, class DatasetAdaptor, int DIM = -1,
  644. typename IndexType = size_t>
  645. class KDTreeBaseClass {
  646. public:
  647. /** Frees the previously-built index. Automatically called within
  648. * buildIndex(). */
  649. void freeIndex(Derived &obj) {
  650. obj.pool.free_all();
  651. obj.root_node = NULL;
  652. obj.m_size_at_index_build = 0;
  653. }
  654. typedef typename Distance::ElementType ElementType;
  655. typedef typename Distance::DistanceType DistanceType;
  656. /*--------------------- Internal Data Structures --------------------------*/
  657. struct Node {
  658. /** Union used because a node can be either a LEAF node or a non-leaf node,
  659. * so both data fields are never used simultaneously */
  660. union {
  661. struct leaf {
  662. IndexType left, right; //!< Indices of points in leaf node
  663. } lr;
  664. struct nonleaf {
  665. int divfeat; //!< Dimension used for subdivision.
  666. DistanceType divlow, divhigh; //!< The values used for subdivision.
  667. } sub;
  668. } node_type;
  669. Node *child1, *child2; //!< Child nodes (both=NULL mean its a leaf node)
  670. };
  671. typedef Node *NodePtr;
  672. struct Interval {
  673. ElementType low, high;
  674. };
  675. /**
  676. * Array of indices to vectors in the dataset.
  677. */
  678. std::vector<IndexType> vind;
  679. NodePtr root_node;
  680. size_t m_leaf_max_size;
  681. size_t m_size; //!< Number of current points in the dataset
  682. size_t m_size_at_index_build; //!< Number of points in the dataset when the
  683. //!< index was built
  684. int dim; //!< Dimensionality of each data point
  685. /** Define "BoundingBox" as a fixed-size or variable-size container depending
  686. * on "DIM" */
  687. typedef
  688. typename array_or_vector_selector<DIM, Interval>::container_t BoundingBox;
  689. /** Define "distance_vector_t" as a fixed-size or variable-size container
  690. * depending on "DIM" */
  691. typedef typename array_or_vector_selector<DIM, DistanceType>::container_t
  692. distance_vector_t;
  693. /** The KD-tree used to find neighbours */
  694. BoundingBox root_bbox;
  695. /**
  696. * Pooled memory allocator.
  697. *
  698. * Using a pooled memory allocator is more efficient
  699. * than allocating memory directly when there is a large
  700. * number small of memory allocations.
  701. */
  702. PooledAllocator pool;
  703. /** Returns number of points in dataset */
  704. size_t size(const Derived &obj) const { return obj.m_size; }
  705. /** Returns the length of each point in the dataset */
  706. size_t veclen(const Derived &obj) {
  707. return static_cast<size_t>(DIM > 0 ? DIM : obj.dim);
  708. }
  709. /// Helper accessor to the dataset points:
  710. inline ElementType dataset_get(const Derived &obj, size_t idx,
  711. int component) const {
  712. return obj.dataset.kdtree_get_pt(idx, component);
  713. }
  714. /**
  715. * Computes the inde memory usage
  716. * Returns: memory used by the index
  717. */
  718. size_t usedMemory(Derived &obj) {
  719. return obj.pool.usedMemory + obj.pool.wastedMemory +
  720. obj.dataset.kdtree_get_point_count() *
  721. sizeof(IndexType); // pool memory and vind array memory
  722. }
  723. void computeMinMax(const Derived &obj, IndexType *ind, IndexType count,
  724. int element, ElementType &min_elem,
  725. ElementType &max_elem) {
  726. min_elem = dataset_get(obj, ind[0], element);
  727. max_elem = dataset_get(obj, ind[0], element);
  728. for (IndexType i = 1; i < count; ++i) {
  729. ElementType val = dataset_get(obj, ind[i], element);
  730. if (val < min_elem)
  731. min_elem = val;
  732. if (val > max_elem)
  733. max_elem = val;
  734. }
  735. }
  736. /**
  737. * Create a tree node that subdivides the list of vecs from vind[first]
  738. * to vind[last]. The routine is called recursively on each sublist.
  739. *
  740. * @param left index of the first vector
  741. * @param right index of the last vector
  742. */
  743. NodePtr divideTree(Derived &obj, const IndexType left, const IndexType right,
  744. BoundingBox &bbox) {
  745. NodePtr node = obj.pool.template allocate<Node>(); // allocate memory
  746. /* If too few exemplars remain, then make this a leaf node. */
  747. if ((right - left) <= static_cast<IndexType>(obj.m_leaf_max_size)) {
  748. node->child1 = node->child2 = NULL; /* Mark as leaf node. */
  749. node->node_type.lr.left = left;
  750. node->node_type.lr.right = right;
  751. // compute bounding-box of leaf points
  752. for (int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) {
  753. bbox[i].low = dataset_get(obj, obj.vind[left], i);
  754. bbox[i].high = dataset_get(obj, obj.vind[left], i);
  755. }
  756. for (IndexType k = left + 1; k < right; ++k) {
  757. for (int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) {
  758. if (bbox[i].low > dataset_get(obj, obj.vind[k], i))
  759. bbox[i].low = dataset_get(obj, obj.vind[k], i);
  760. if (bbox[i].high < dataset_get(obj, obj.vind[k], i))
  761. bbox[i].high = dataset_get(obj, obj.vind[k], i);
  762. }
  763. }
  764. } else {
  765. IndexType idx;
  766. int cutfeat;
  767. DistanceType cutval;
  768. middleSplit_(obj, &obj.vind[0] + left, right - left, idx, cutfeat, cutval,
  769. bbox);
  770. node->node_type.sub.divfeat = cutfeat;
  771. BoundingBox left_bbox(bbox);
  772. left_bbox[cutfeat].high = cutval;
  773. node->child1 = divideTree(obj, left, left + idx, left_bbox);
  774. BoundingBox right_bbox(bbox);
  775. right_bbox[cutfeat].low = cutval;
  776. node->child2 = divideTree(obj, left + idx, right, right_bbox);
  777. node->node_type.sub.divlow = left_bbox[cutfeat].high;
  778. node->node_type.sub.divhigh = right_bbox[cutfeat].low;
  779. for (int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) {
  780. bbox[i].low = std::min(left_bbox[i].low, right_bbox[i].low);
  781. bbox[i].high = std::max(left_bbox[i].high, right_bbox[i].high);
  782. }
  783. }
  784. return node;
  785. }
  786. void middleSplit_(Derived &obj, IndexType *ind, IndexType count,
  787. IndexType &index, int &cutfeat, DistanceType &cutval,
  788. const BoundingBox &bbox) {
  789. const DistanceType EPS = static_cast<DistanceType>(0.00001);
  790. ElementType max_span = bbox[0].high - bbox[0].low;
  791. for (int i = 1; i < (DIM > 0 ? DIM : obj.dim); ++i) {
  792. ElementType span = bbox[i].high - bbox[i].low;
  793. if (span > max_span) {
  794. max_span = span;
  795. }
  796. }
  797. ElementType max_spread = -1;
  798. cutfeat = 0;
  799. for (int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) {
  800. ElementType span = bbox[i].high - bbox[i].low;
  801. if (span > (1 - EPS) * max_span) {
  802. ElementType min_elem, max_elem;
  803. computeMinMax(obj, ind, count, i, min_elem, max_elem);
  804. ElementType spread = max_elem - min_elem;
  805. if (spread > max_spread) {
  806. cutfeat = i;
  807. max_spread = spread;
  808. }
  809. }
  810. }
  811. // split in the middle
  812. DistanceType split_val = (bbox[cutfeat].low + bbox[cutfeat].high) / 2;
  813. ElementType min_elem, max_elem;
  814. computeMinMax(obj, ind, count, cutfeat, min_elem, max_elem);
  815. if (split_val < min_elem)
  816. cutval = min_elem;
  817. else if (split_val > max_elem)
  818. cutval = max_elem;
  819. else
  820. cutval = split_val;
  821. IndexType lim1, lim2;
  822. planeSplit(obj, ind, count, cutfeat, cutval, lim1, lim2);
  823. if (lim1 > count / 2)
  824. index = lim1;
  825. else if (lim2 < count / 2)
  826. index = lim2;
  827. else
  828. index = count / 2;
  829. }
  830. /**
  831. * Subdivide the list of points by a plane perpendicular on axe corresponding
  832. * to the 'cutfeat' dimension at 'cutval' position.
  833. *
  834. * On return:
  835. * dataset[ind[0..lim1-1]][cutfeat]<cutval
  836. * dataset[ind[lim1..lim2-1]][cutfeat]==cutval
  837. * dataset[ind[lim2..count]][cutfeat]>cutval
  838. */
  839. void planeSplit(Derived &obj, IndexType *ind, const IndexType count,
  840. int cutfeat, DistanceType &cutval, IndexType &lim1,
  841. IndexType &lim2) {
  842. /* Move vector indices for left subtree to front of list. */
  843. IndexType left = 0;
  844. IndexType right = count - 1;
  845. for (;;) {
  846. while (left <= right && dataset_get(obj, ind[left], cutfeat) < cutval)
  847. ++left;
  848. while (right && left <= right &&
  849. dataset_get(obj, ind[right], cutfeat) >= cutval)
  850. --right;
  851. if (left > right || !right)
  852. break; // "!right" was added to support unsigned Index types
  853. std::swap(ind[left], ind[right]);
  854. ++left;
  855. --right;
  856. }
  857. /* If either list is empty, it means that all remaining features
  858. * are identical. Split in the middle to maintain a balanced tree.
  859. */
  860. lim1 = left;
  861. right = count - 1;
  862. for (;;) {
  863. while (left <= right && dataset_get(obj, ind[left], cutfeat) <= cutval)
  864. ++left;
  865. while (right && left <= right &&
  866. dataset_get(obj, ind[right], cutfeat) > cutval)
  867. --right;
  868. if (left > right || !right)
  869. break; // "!right" was added to support unsigned Index types
  870. std::swap(ind[left], ind[right]);
  871. ++left;
  872. --right;
  873. }
  874. lim2 = left;
  875. }
  876. DistanceType computeInitialDistances(const Derived &obj,
  877. const ElementType *vec,
  878. distance_vector_t &dists) const {
  879. assert(vec);
  880. DistanceType distsq = DistanceType();
  881. for (int i = 0; i < (DIM > 0 ? DIM : obj.dim); ++i) {
  882. if (vec[i] < obj.root_bbox[i].low) {
  883. dists[i] = obj.distance.accum_dist(vec[i], obj.root_bbox[i].low, i);
  884. distsq += dists[i];
  885. }
  886. if (vec[i] > obj.root_bbox[i].high) {
  887. dists[i] = obj.distance.accum_dist(vec[i], obj.root_bbox[i].high, i);
  888. distsq += dists[i];
  889. }
  890. }
  891. return distsq;
  892. }
  893. void save_tree(Derived &obj, FILE *stream, NodePtr tree) {
  894. save_value(stream, *tree);
  895. if (tree->child1 != NULL) {
  896. save_tree(obj, stream, tree->child1);
  897. }
  898. if (tree->child2 != NULL) {
  899. save_tree(obj, stream, tree->child2);
  900. }
  901. }
  902. void load_tree(Derived &obj, FILE *stream, NodePtr &tree) {
  903. tree = obj.pool.template allocate<Node>();
  904. load_value(stream, *tree);
  905. if (tree->child1 != NULL) {
  906. load_tree(obj, stream, tree->child1);
  907. }
  908. if (tree->child2 != NULL) {
  909. load_tree(obj, stream, tree->child2);
  910. }
  911. }
  912. /** Stores the index in a binary file.
  913. * IMPORTANT NOTE: The set of data points is NOT stored in the file, so when
  914. * loading the index object it must be constructed associated to the same
  915. * source of data points used while building it. See the example:
  916. * examples/saveload_example.cpp \sa loadIndex */
  917. void saveIndex_(Derived &obj, FILE *stream) {
  918. save_value(stream, obj.m_size);
  919. save_value(stream, obj.dim);
  920. save_value(stream, obj.root_bbox);
  921. save_value(stream, obj.m_leaf_max_size);
  922. save_value(stream, obj.vind);
  923. save_tree(obj, stream, obj.root_node);
  924. }
  925. /** Loads a previous index from a binary file.
  926. * IMPORTANT NOTE: The set of data points is NOT stored in the file, so the
  927. * index object must be constructed associated to the same source of data
  928. * points used while building the index. See the example:
  929. * examples/saveload_example.cpp \sa loadIndex */
  930. void loadIndex_(Derived &obj, FILE *stream) {
  931. load_value(stream, obj.m_size);
  932. load_value(stream, obj.dim);
  933. load_value(stream, obj.root_bbox);
  934. load_value(stream, obj.m_leaf_max_size);
  935. load_value(stream, obj.vind);
  936. load_tree(obj, stream, obj.root_node);
  937. }
  938. };
  939. /** @addtogroup kdtrees_grp KD-tree classes and adaptors
  940. * @{ */
  941. /** kd-tree static index
  942. *
  943. * Contains the k-d trees and other information for indexing a set of points
  944. * for nearest-neighbor matching.
  945. *
  946. * The class "DatasetAdaptor" must provide the following interface (can be
  947. * non-virtual, inlined methods):
  948. *
  949. * \code
  950. * // Must return the number of data poins
  951. * inline size_t kdtree_get_point_count() const { ... }
  952. *
  953. *
  954. * // Must return the dim'th component of the idx'th point in the class:
  955. * inline T kdtree_get_pt(const size_t idx, const size_t dim) const { ... }
  956. *
  957. * // Optional bounding-box computation: return false to default to a standard
  958. * bbox computation loop.
  959. * // Return true if the BBOX was already computed by the class and returned
  960. * in "bb" so it can be avoided to redo it again.
  961. * // Look at bb.size() to find out the expected dimensionality (e.g. 2 or 3
  962. * for point clouds) template <class BBOX> bool kdtree_get_bbox(BBOX &bb) const
  963. * {
  964. * bb[0].low = ...; bb[0].high = ...; // 0th dimension limits
  965. * bb[1].low = ...; bb[1].high = ...; // 1st dimension limits
  966. * ...
  967. * return true;
  968. * }
  969. *
  970. * \endcode
  971. *
  972. * \tparam DatasetAdaptor The user-provided adaptor (see comments above).
  973. * \tparam Distance The distance metric to use: nanoflann::metric_L1,
  974. * nanoflann::metric_L2, nanoflann::metric_L2_Simple, etc. \tparam DIM
  975. * Dimensionality of data points (e.g. 3 for 3D points) \tparam IndexType Will
  976. * be typically size_t or int
  977. */
  978. template <typename Distance, class DatasetAdaptor, int DIM = -1,
  979. typename IndexType = size_t>
  980. class KDTreeSingleIndexAdaptor
  981. : public KDTreeBaseClass<
  982. KDTreeSingleIndexAdaptor<Distance, DatasetAdaptor, DIM, IndexType>,
  983. Distance, DatasetAdaptor, DIM, IndexType> {
  984. public:
  985. /** Deleted copy constructor*/
  986. KDTreeSingleIndexAdaptor(
  987. const KDTreeSingleIndexAdaptor<Distance, DatasetAdaptor, DIM, IndexType>
  988. &) = delete;
  989. /**
  990. * The dataset used by this index
  991. */
  992. const DatasetAdaptor &dataset; //!< The source of our data
  993. const KDTreeSingleIndexAdaptorParams index_params;
  994. Distance distance;
  995. typedef typename nanoflann::KDTreeBaseClass<
  996. nanoflann::KDTreeSingleIndexAdaptor<Distance, DatasetAdaptor, DIM,
  997. IndexType>,
  998. Distance, DatasetAdaptor, DIM, IndexType>
  999. BaseClassRef;
  1000. typedef typename BaseClassRef::ElementType ElementType;
  1001. typedef typename BaseClassRef::DistanceType DistanceType;
  1002. typedef typename BaseClassRef::Node Node;
  1003. typedef Node *NodePtr;
  1004. typedef typename BaseClassRef::Interval Interval;
  1005. /** Define "BoundingBox" as a fixed-size or variable-size container depending
  1006. * on "DIM" */
  1007. typedef typename BaseClassRef::BoundingBox BoundingBox;
  1008. /** Define "distance_vector_t" as a fixed-size or variable-size container
  1009. * depending on "DIM" */
  1010. typedef typename BaseClassRef::distance_vector_t distance_vector_t;
  1011. /**
  1012. * KDTree constructor
  1013. *
  1014. * Refer to docs in README.md or online in
  1015. * https://github.com/jlblancoc/nanoflann
  1016. *
  1017. * The KD-Tree point dimension (the length of each point in the datase, e.g. 3
  1018. * for 3D points) is determined by means of:
  1019. * - The \a DIM template parameter if >0 (highest priority)
  1020. * - Otherwise, the \a dimensionality parameter of this constructor.
  1021. *
  1022. * @param inputData Dataset with the input features
  1023. * @param params Basically, the maximum leaf node size
  1024. */
  1025. KDTreeSingleIndexAdaptor(const int dimensionality,
  1026. const DatasetAdaptor &inputData,
  1027. const KDTreeSingleIndexAdaptorParams &params =
  1028. KDTreeSingleIndexAdaptorParams())
  1029. : dataset(inputData), index_params(params), distance(inputData) {
  1030. BaseClassRef::root_node = NULL;
  1031. BaseClassRef::m_size = dataset.kdtree_get_point_count();
  1032. BaseClassRef::m_size_at_index_build = BaseClassRef::m_size;
  1033. BaseClassRef::dim = dimensionality;
  1034. if (DIM > 0)
  1035. BaseClassRef::dim = DIM;
  1036. BaseClassRef::m_leaf_max_size = params.leaf_max_size;
  1037. // Create a permutable array of indices to the input vectors.
  1038. init_vind();
  1039. }
  1040. /**
  1041. * Builds the index
  1042. */
  1043. void buildIndex() {
  1044. BaseClassRef::m_size = dataset.kdtree_get_point_count();
  1045. BaseClassRef::m_size_at_index_build = BaseClassRef::m_size;
  1046. init_vind();
  1047. this->freeIndex(*this);
  1048. BaseClassRef::m_size_at_index_build = BaseClassRef::m_size;
  1049. if (BaseClassRef::m_size == 0)
  1050. return;
  1051. computeBoundingBox(BaseClassRef::root_bbox);
  1052. BaseClassRef::root_node =
  1053. this->divideTree(*this, 0, BaseClassRef::m_size,
  1054. BaseClassRef::root_bbox); // construct the tree
  1055. }
  1056. /** \name Query methods
  1057. * @{ */
  1058. /**
  1059. * Find set of nearest neighbors to vec[0:dim-1]. Their indices are stored
  1060. * inside the result object.
  1061. *
  1062. * Params:
  1063. * result = the result object in which the indices of the
  1064. * nearest-neighbors are stored vec = the vector for which to search the
  1065. * nearest neighbors
  1066. *
  1067. * \tparam RESULTSET Should be any ResultSet<DistanceType>
  1068. * \return True if the requested neighbors could be found.
  1069. * \sa knnSearch, radiusSearch
  1070. */
  1071. template <typename RESULTSET>
  1072. bool findNeighbors(RESULTSET &result, const ElementType *vec,
  1073. const SearchParams &searchParams) const {
  1074. assert(vec);
  1075. if (this->size(*this) == 0)
  1076. return false;
  1077. if (!BaseClassRef::root_node)
  1078. throw std::runtime_error(
  1079. "[nanoflann] findNeighbors() called before building the index.");
  1080. float epsError = 1 + searchParams.eps;
  1081. distance_vector_t
  1082. dists; // fixed or variable-sized container (depending on DIM)
  1083. auto zero = static_cast<decltype(result.worstDist())>(0);
  1084. assign(dists, (DIM > 0 ? DIM : BaseClassRef::dim),
  1085. zero); // Fill it with zeros.
  1086. DistanceType distsq = this->computeInitialDistances(*this, vec, dists);
  1087. searchLevel(result, vec, BaseClassRef::root_node, distsq, dists,
  1088. epsError); // "count_leaf" parameter removed since was neither
  1089. // used nor returned to the user.
  1090. return result.full();
  1091. }
  1092. /**
  1093. * Find the "num_closest" nearest neighbors to the \a query_point[0:dim-1].
  1094. * Their indices are stored inside the result object. \sa radiusSearch,
  1095. * findNeighbors \note nChecks_IGNORED is ignored but kept for compatibility
  1096. * with the original FLANN interface. \return Number `N` of valid points in
  1097. * the result set. Only the first `N` entries in `out_indices` and
  1098. * `out_distances_sq` will be valid. Return may be less than `num_closest`
  1099. * only if the number of elements in the tree is less than `num_closest`.
  1100. */
  1101. size_t knnSearch(const ElementType *query_point, const size_t num_closest,
  1102. IndexType *out_indices, DistanceType *out_distances_sq,
  1103. const int /* nChecks_IGNORED */ = 10) const {
  1104. nanoflann::KNNResultSet<DistanceType, IndexType> resultSet(num_closest);
  1105. resultSet.init(out_indices, out_distances_sq);
  1106. this->findNeighbors(resultSet, query_point, nanoflann::SearchParams());
  1107. return resultSet.size();
  1108. }
  1109. /**
  1110. * Find all the neighbors to \a query_point[0:dim-1] within a maximum radius.
  1111. * The output is given as a vector of pairs, of which the first element is a
  1112. * point index and the second the corresponding distance. Previous contents of
  1113. * \a IndicesDists are cleared.
  1114. *
  1115. * If searchParams.sorted==true, the output list is sorted by ascending
  1116. * distances.
  1117. *
  1118. * For a better performance, it is advisable to do a .reserve() on the vector
  1119. * if you have any wild guess about the number of expected matches.
  1120. *
  1121. * \sa knnSearch, findNeighbors, radiusSearchCustomCallback
  1122. * \return The number of points within the given radius (i.e. indices.size()
  1123. * or dists.size() )
  1124. */
  1125. size_t
  1126. radiusSearch(const ElementType *query_point, const DistanceType &radius,
  1127. std::vector<std::pair<IndexType, DistanceType>> &IndicesDists,
  1128. const SearchParams &searchParams) const {
  1129. RadiusResultSet<DistanceType, IndexType> resultSet(radius, IndicesDists);
  1130. const size_t nFound =
  1131. radiusSearchCustomCallback(query_point, resultSet, searchParams);
  1132. if (searchParams.sorted)
  1133. std::sort(IndicesDists.begin(), IndicesDists.end(), IndexDist_Sorter());
  1134. return nFound;
  1135. }
  1136. /**
  1137. * Just like radiusSearch() but with a custom callback class for each point
  1138. * found in the radius of the query. See the source of RadiusResultSet<> as a
  1139. * start point for your own classes. \sa radiusSearch
  1140. */
  1141. template <class SEARCH_CALLBACK>
  1142. size_t radiusSearchCustomCallback(
  1143. const ElementType *query_point, SEARCH_CALLBACK &resultSet,
  1144. const SearchParams &searchParams = SearchParams()) const {
  1145. this->findNeighbors(resultSet, query_point, searchParams);
  1146. return resultSet.size();
  1147. }
  1148. /** @} */
  1149. public:
  1150. /** Make sure the auxiliary list \a vind has the same size than the current
  1151. * dataset, and re-generate if size has changed. */
  1152. void init_vind() {
  1153. // Create a permutable array of indices to the input vectors.
  1154. BaseClassRef::m_size = dataset.kdtree_get_point_count();
  1155. if (BaseClassRef::vind.size() != BaseClassRef::m_size)
  1156. BaseClassRef::vind.resize(BaseClassRef::m_size);
  1157. for (size_t i = 0; i < BaseClassRef::m_size; i++)
  1158. BaseClassRef::vind[i] = i;
  1159. }
  1160. void computeBoundingBox(BoundingBox &bbox) {
  1161. resize(bbox, (DIM > 0 ? DIM : BaseClassRef::dim));
  1162. if (dataset.kdtree_get_bbox(bbox)) {
  1163. // Done! It was implemented in derived class
  1164. } else {
  1165. const size_t N = dataset.kdtree_get_point_count();
  1166. if (!N)
  1167. throw std::runtime_error("[nanoflann] computeBoundingBox() called but "
  1168. "no data points found.");
  1169. for (int i = 0; i < (DIM > 0 ? DIM : BaseClassRef::dim); ++i) {
  1170. bbox[i].low = bbox[i].high = this->dataset_get(*this, 0, i);
  1171. }
  1172. for (size_t k = 1; k < N; ++k) {
  1173. for (int i = 0; i < (DIM > 0 ? DIM : BaseClassRef::dim); ++i) {
  1174. if (this->dataset_get(*this, k, i) < bbox[i].low)
  1175. bbox[i].low = this->dataset_get(*this, k, i);
  1176. if (this->dataset_get(*this, k, i) > bbox[i].high)
  1177. bbox[i].high = this->dataset_get(*this, k, i);
  1178. }
  1179. }
  1180. }
  1181. }
  1182. /**
  1183. * Performs an exact search in the tree starting from a node.
  1184. * \tparam RESULTSET Should be any ResultSet<DistanceType>
  1185. * \return true if the search should be continued, false if the results are
  1186. * sufficient
  1187. */
  1188. template <class RESULTSET>
  1189. bool searchLevel(RESULTSET &result_set, const ElementType *vec,
  1190. const NodePtr node, DistanceType mindistsq,
  1191. distance_vector_t &dists, const float epsError) const {
  1192. /* If this is a leaf node, then do check and return. */
  1193. if ((node->child1 == NULL) && (node->child2 == NULL)) {
  1194. // count_leaf += (node->lr.right-node->lr.left); // Removed since was
  1195. // neither used nor returned to the user.
  1196. DistanceType worst_dist = result_set.worstDist();
  1197. for (IndexType i = node->node_type.lr.left; i < node->node_type.lr.right;
  1198. ++i) {
  1199. const IndexType index = BaseClassRef::vind[i]; // reorder... : i;
  1200. DistanceType dist = distance.evalMetric(
  1201. vec, index, (DIM > 0 ? DIM : BaseClassRef::dim));
  1202. if (dist < worst_dist) {
  1203. if (!result_set.addPoint(dist, BaseClassRef::vind[i])) {
  1204. // the resultset doesn't want to receive any more points, we're done
  1205. // searching!
  1206. return false;
  1207. }
  1208. }
  1209. }
  1210. return true;
  1211. }
  1212. /* Which child branch should be taken first? */
  1213. int idx = node->node_type.sub.divfeat;
  1214. ElementType val = vec[idx];
  1215. DistanceType diff1 = val - node->node_type.sub.divlow;
  1216. DistanceType diff2 = val - node->node_type.sub.divhigh;
  1217. NodePtr bestChild;
  1218. NodePtr otherChild;
  1219. DistanceType cut_dist;
  1220. if ((diff1 + diff2) < 0) {
  1221. bestChild = node->child1;
  1222. otherChild = node->child2;
  1223. cut_dist = distance.accum_dist(val, node->node_type.sub.divhigh, idx);
  1224. } else {
  1225. bestChild = node->child2;
  1226. otherChild = node->child1;
  1227. cut_dist = distance.accum_dist(val, node->node_type.sub.divlow, idx);
  1228. }
  1229. /* Call recursively to search next level down. */
  1230. if (!searchLevel(result_set, vec, bestChild, mindistsq, dists, epsError)) {
  1231. // the resultset doesn't want to receive any more points, we're done
  1232. // searching!
  1233. return false;
  1234. }
  1235. DistanceType dst = dists[idx];
  1236. mindistsq = mindistsq + cut_dist - dst;
  1237. dists[idx] = cut_dist;
  1238. if (mindistsq * epsError <= result_set.worstDist()) {
  1239. if (!searchLevel(result_set, vec, otherChild, mindistsq, dists,
  1240. epsError)) {
  1241. // the resultset doesn't want to receive any more points, we're done
  1242. // searching!
  1243. return false;
  1244. }
  1245. }
  1246. dists[idx] = dst;
  1247. return true;
  1248. }
  1249. public:
  1250. /** Stores the index in a binary file.
  1251. * IMPORTANT NOTE: The set of data points is NOT stored in the file, so when
  1252. * loading the index object it must be constructed associated to the same
  1253. * source of data points used while building it. See the example:
  1254. * examples/saveload_example.cpp \sa loadIndex */
  1255. void saveIndex(FILE *stream) { this->saveIndex_(*this, stream); }
  1256. /** Loads a previous index from a binary file.
  1257. * IMPORTANT NOTE: The set of data points is NOT stored in the file, so the
  1258. * index object must be constructed associated to the same source of data
  1259. * points used while building the index. See the example:
  1260. * examples/saveload_example.cpp \sa loadIndex */
  1261. void loadIndex(FILE *stream) { this->loadIndex_(*this, stream); }
  1262. }; // class KDTree
  1263. /** kd-tree dynamic index
  1264. *
  1265. * Contains the k-d trees and other information for indexing a set of points
  1266. * for nearest-neighbor matching.
  1267. *
  1268. * The class "DatasetAdaptor" must provide the following interface (can be
  1269. * non-virtual, inlined methods):
  1270. *
  1271. * \code
  1272. * // Must return the number of data poins
  1273. * inline size_t kdtree_get_point_count() const { ... }
  1274. *
  1275. * // Must return the dim'th component of the idx'th point in the class:
  1276. * inline T kdtree_get_pt(const size_t idx, const size_t dim) const { ... }
  1277. *
  1278. * // Optional bounding-box computation: return false to default to a standard
  1279. * bbox computation loop.
  1280. * // Return true if the BBOX was already computed by the class and returned
  1281. * in "bb" so it can be avoided to redo it again.
  1282. * // Look at bb.size() to find out the expected dimensionality (e.g. 2 or 3
  1283. * for point clouds) template <class BBOX> bool kdtree_get_bbox(BBOX &bb) const
  1284. * {
  1285. * bb[0].low = ...; bb[0].high = ...; // 0th dimension limits
  1286. * bb[1].low = ...; bb[1].high = ...; // 1st dimension limits
  1287. * ...
  1288. * return true;
  1289. * }
  1290. *
  1291. * \endcode
  1292. *
  1293. * \tparam DatasetAdaptor The user-provided adaptor (see comments above).
  1294. * \tparam Distance The distance metric to use: nanoflann::metric_L1,
  1295. * nanoflann::metric_L2, nanoflann::metric_L2_Simple, etc. \tparam DIM
  1296. * Dimensionality of data points (e.g. 3 for 3D points) \tparam IndexType Will
  1297. * be typically size_t or int
  1298. */
  1299. template <typename Distance, class DatasetAdaptor, int DIM = -1,
  1300. typename IndexType = size_t>
  1301. class KDTreeSingleIndexDynamicAdaptor_
  1302. : public KDTreeBaseClass<KDTreeSingleIndexDynamicAdaptor_<
  1303. Distance, DatasetAdaptor, DIM, IndexType>,
  1304. Distance, DatasetAdaptor, DIM, IndexType> {
  1305. public:
  1306. /**
  1307. * The dataset used by this index
  1308. */
  1309. const DatasetAdaptor &dataset; //!< The source of our data
  1310. KDTreeSingleIndexAdaptorParams index_params;
  1311. std::vector<int> &treeIndex;
  1312. Distance distance;
  1313. typedef typename nanoflann::KDTreeBaseClass<
  1314. nanoflann::KDTreeSingleIndexDynamicAdaptor_<Distance, DatasetAdaptor, DIM,
  1315. IndexType>,
  1316. Distance, DatasetAdaptor, DIM, IndexType>
  1317. BaseClassRef;
  1318. typedef typename BaseClassRef::ElementType ElementType;
  1319. typedef typename BaseClassRef::DistanceType DistanceType;
  1320. typedef typename BaseClassRef::Node Node;
  1321. typedef Node *NodePtr;
  1322. typedef typename BaseClassRef::Interval Interval;
  1323. /** Define "BoundingBox" as a fixed-size or variable-size container depending
  1324. * on "DIM" */
  1325. typedef typename BaseClassRef::BoundingBox BoundingBox;
  1326. /** Define "distance_vector_t" as a fixed-size or variable-size container
  1327. * depending on "DIM" */
  1328. typedef typename BaseClassRef::distance_vector_t distance_vector_t;
  1329. /**
  1330. * KDTree constructor
  1331. *
  1332. * Refer to docs in README.md or online in
  1333. * https://github.com/jlblancoc/nanoflann
  1334. *
  1335. * The KD-Tree point dimension (the length of each point in the datase, e.g. 3
  1336. * for 3D points) is determined by means of:
  1337. * - The \a DIM template parameter if >0 (highest priority)
  1338. * - Otherwise, the \a dimensionality parameter of this constructor.
  1339. *
  1340. * @param inputData Dataset with the input features
  1341. * @param params Basically, the maximum leaf node size
  1342. */
  1343. KDTreeSingleIndexDynamicAdaptor_(
  1344. const int dimensionality, const DatasetAdaptor &inputData,
  1345. std::vector<int> &treeIndex_,
  1346. const KDTreeSingleIndexAdaptorParams &params =
  1347. KDTreeSingleIndexAdaptorParams())
  1348. : dataset(inputData), index_params(params), treeIndex(treeIndex_),
  1349. distance(inputData) {
  1350. BaseClassRef::root_node = NULL;
  1351. BaseClassRef::m_size = 0;
  1352. BaseClassRef::m_size_at_index_build = 0;
  1353. BaseClassRef::dim = dimensionality;
  1354. if (DIM > 0)
  1355. BaseClassRef::dim = DIM;
  1356. BaseClassRef::m_leaf_max_size = params.leaf_max_size;
  1357. }
  1358. /** Assignment operator definiton */
  1359. KDTreeSingleIndexDynamicAdaptor_
  1360. operator=(const KDTreeSingleIndexDynamicAdaptor_ &rhs) {
  1361. KDTreeSingleIndexDynamicAdaptor_ tmp(rhs);
  1362. std::swap(BaseClassRef::vind, tmp.BaseClassRef::vind);
  1363. std::swap(BaseClassRef::m_leaf_max_size, tmp.BaseClassRef::m_leaf_max_size);
  1364. std::swap(index_params, tmp.index_params);
  1365. std::swap(treeIndex, tmp.treeIndex);
  1366. std::swap(BaseClassRef::m_size, tmp.BaseClassRef::m_size);
  1367. std::swap(BaseClassRef::m_size_at_index_build,
  1368. tmp.BaseClassRef::m_size_at_index_build);
  1369. std::swap(BaseClassRef::root_node, tmp.BaseClassRef::root_node);
  1370. std::swap(BaseClassRef::root_bbox, tmp.BaseClassRef::root_bbox);
  1371. std::swap(BaseClassRef::pool, tmp.BaseClassRef::pool);
  1372. return *this;
  1373. }
  1374. /**
  1375. * Builds the index
  1376. */
  1377. void buildIndex() {
  1378. BaseClassRef::m_size = BaseClassRef::vind.size();
  1379. this->freeIndex(*this);
  1380. BaseClassRef::m_size_at_index_build = BaseClassRef::m_size;
  1381. if (BaseClassRef::m_size == 0)
  1382. return;
  1383. computeBoundingBox(BaseClassRef::root_bbox);
  1384. BaseClassRef::root_node =
  1385. this->divideTree(*this, 0, BaseClassRef::m_size,
  1386. BaseClassRef::root_bbox); // construct the tree
  1387. }
  1388. /** \name Query methods
  1389. * @{ */
  1390. /**
  1391. * Find set of nearest neighbors to vec[0:dim-1]. Their indices are stored
  1392. * inside the result object.
  1393. *
  1394. * Params:
  1395. * result = the result object in which the indices of the
  1396. * nearest-neighbors are stored vec = the vector for which to search the
  1397. * nearest neighbors
  1398. *
  1399. * \tparam RESULTSET Should be any ResultSet<DistanceType>
  1400. * \return True if the requested neighbors could be found.
  1401. * \sa knnSearch, radiusSearch
  1402. */
  1403. template <typename RESULTSET>
  1404. bool findNeighbors(RESULTSET &result, const ElementType *vec,
  1405. const SearchParams &searchParams) const {
  1406. assert(vec);
  1407. if (this->size(*this) == 0)
  1408. return false;
  1409. if (!BaseClassRef::root_node)
  1410. return false;
  1411. float epsError = 1 + searchParams.eps;
  1412. // fixed or variable-sized container (depending on DIM)
  1413. distance_vector_t dists;
  1414. // Fill it with zeros.
  1415. assign(dists, (DIM > 0 ? DIM : BaseClassRef::dim),
  1416. static_cast<typename distance_vector_t::value_type>(0));
  1417. DistanceType distsq = this->computeInitialDistances(*this, vec, dists);
  1418. searchLevel(result, vec, BaseClassRef::root_node, distsq, dists,
  1419. epsError); // "count_leaf" parameter removed since was neither
  1420. // used nor returned to the user.
  1421. return result.full();
  1422. }
  1423. /**
  1424. * Find the "num_closest" nearest neighbors to the \a query_point[0:dim-1].
  1425. * Their indices are stored inside the result object. \sa radiusSearch,
  1426. * findNeighbors \note nChecks_IGNORED is ignored but kept for compatibility
  1427. * with the original FLANN interface. \return Number `N` of valid points in
  1428. * the result set. Only the first `N` entries in `out_indices` and
  1429. * `out_distances_sq` will be valid. Return may be less than `num_closest`
  1430. * only if the number of elements in the tree is less than `num_closest`.
  1431. */
  1432. size_t knnSearch(const ElementType *query_point, const size_t num_closest,
  1433. IndexType *out_indices, DistanceType *out_distances_sq,
  1434. const int /* nChecks_IGNORED */ = 10) const {
  1435. nanoflann::KNNResultSet<DistanceType, IndexType> resultSet(num_closest);
  1436. resultSet.init(out_indices, out_distances_sq);
  1437. this->findNeighbors(resultSet, query_point, nanoflann::SearchParams());
  1438. return resultSet.size();
  1439. }
  1440. /**
  1441. * Find all the neighbors to \a query_point[0:dim-1] within a maximum radius.
  1442. * The output is given as a vector of pairs, of which the first element is a
  1443. * point index and the second the corresponding distance. Previous contents of
  1444. * \a IndicesDists are cleared.
  1445. *
  1446. * If searchParams.sorted==true, the output list is sorted by ascending
  1447. * distances.
  1448. *
  1449. * For a better performance, it is advisable to do a .reserve() on the vector
  1450. * if you have any wild guess about the number of expected matches.
  1451. *
  1452. * \sa knnSearch, findNeighbors, radiusSearchCustomCallback
  1453. * \return The number of points within the given radius (i.e. indices.size()
  1454. * or dists.size() )
  1455. */
  1456. size_t
  1457. radiusSearch(const ElementType *query_point, const DistanceType &radius,
  1458. std::vector<std::pair<IndexType, DistanceType>> &IndicesDists,
  1459. const SearchParams &searchParams) const {
  1460. RadiusResultSet<DistanceType, IndexType> resultSet(radius, IndicesDists);
  1461. const size_t nFound =
  1462. radiusSearchCustomCallback(query_point, resultSet, searchParams);
  1463. if (searchParams.sorted)
  1464. std::sort(IndicesDists.begin(), IndicesDists.end(), IndexDist_Sorter());
  1465. return nFound;
  1466. }
  1467. /**
  1468. * Just like radiusSearch() but with a custom callback class for each point
  1469. * found in the radius of the query. See the source of RadiusResultSet<> as a
  1470. * start point for your own classes. \sa radiusSearch
  1471. */
  1472. template <class SEARCH_CALLBACK>
  1473. size_t radiusSearchCustomCallback(
  1474. const ElementType *query_point, SEARCH_CALLBACK &resultSet,
  1475. const SearchParams &searchParams = SearchParams()) const {
  1476. this->findNeighbors(resultSet, query_point, searchParams);
  1477. return resultSet.size();
  1478. }
  1479. /** @} */
  1480. public:
  1481. void computeBoundingBox(BoundingBox &bbox) {
  1482. resize(bbox, (DIM > 0 ? DIM : BaseClassRef::dim));
  1483. if (dataset.kdtree_get_bbox(bbox)) {
  1484. // Done! It was implemented in derived class
  1485. } else {
  1486. const size_t N = BaseClassRef::m_size;
  1487. if (!N)
  1488. throw std::runtime_error("[nanoflann] computeBoundingBox() called but "
  1489. "no data points found.");
  1490. for (int i = 0; i < (DIM > 0 ? DIM : BaseClassRef::dim); ++i) {
  1491. bbox[i].low = bbox[i].high =
  1492. this->dataset_get(*this, BaseClassRef::vind[0], i);
  1493. }
  1494. for (size_t k = 1; k < N; ++k) {
  1495. for (int i = 0; i < (DIM > 0 ? DIM : BaseClassRef::dim); ++i) {
  1496. if (this->dataset_get(*this, BaseClassRef::vind[k], i) < bbox[i].low)
  1497. bbox[i].low = this->dataset_get(*this, BaseClassRef::vind[k], i);
  1498. if (this->dataset_get(*this, BaseClassRef::vind[k], i) > bbox[i].high)
  1499. bbox[i].high = this->dataset_get(*this, BaseClassRef::vind[k], i);
  1500. }
  1501. }
  1502. }
  1503. }
  1504. /**
  1505. * Performs an exact search in the tree starting from a node.
  1506. * \tparam RESULTSET Should be any ResultSet<DistanceType>
  1507. */
  1508. template <class RESULTSET>
  1509. void searchLevel(RESULTSET &result_set, const ElementType *vec,
  1510. const NodePtr node, DistanceType mindistsq,
  1511. distance_vector_t &dists, const float epsError) const {
  1512. /* If this is a leaf node, then do check and return. */
  1513. if ((node->child1 == NULL) && (node->child2 == NULL)) {
  1514. // count_leaf += (node->lr.right-node->lr.left); // Removed since was
  1515. // neither used nor returned to the user.
  1516. DistanceType worst_dist = result_set.worstDist();
  1517. for (IndexType i = node->node_type.lr.left; i < node->node_type.lr.right;
  1518. ++i) {
  1519. const IndexType index = BaseClassRef::vind[i]; // reorder... : i;
  1520. if (treeIndex[index] == -1)
  1521. continue;
  1522. DistanceType dist = distance.evalMetric(
  1523. vec, index, (DIM > 0 ? DIM : BaseClassRef::dim));
  1524. if (dist < worst_dist) {
  1525. if (!result_set.addPoint(
  1526. static_cast<typename RESULTSET::DistanceType>(dist),
  1527. static_cast<typename RESULTSET::IndexType>(
  1528. BaseClassRef::vind[i]))) {
  1529. // the resultset doesn't want to receive any more points, we're done
  1530. // searching!
  1531. return; // false;
  1532. }
  1533. }
  1534. }
  1535. return;
  1536. }
  1537. /* Which child branch should be taken first? */
  1538. int idx = node->node_type.sub.divfeat;
  1539. ElementType val = vec[idx];
  1540. DistanceType diff1 = val - node->node_type.sub.divlow;
  1541. DistanceType diff2 = val - node->node_type.sub.divhigh;
  1542. NodePtr bestChild;
  1543. NodePtr otherChild;
  1544. DistanceType cut_dist;
  1545. if ((diff1 + diff2) < 0) {
  1546. bestChild = node->child1;
  1547. otherChild = node->child2;
  1548. cut_dist = distance.accum_dist(val, node->node_type.sub.divhigh, idx);
  1549. } else {
  1550. bestChild = node->child2;
  1551. otherChild = node->child1;
  1552. cut_dist = distance.accum_dist(val, node->node_type.sub.divlow, idx);
  1553. }
  1554. /* Call recursively to search next level down. */
  1555. searchLevel(result_set, vec, bestChild, mindistsq, dists, epsError);
  1556. DistanceType dst = dists[idx];
  1557. mindistsq = mindistsq + cut_dist - dst;
  1558. dists[idx] = cut_dist;
  1559. if (mindistsq * epsError <= result_set.worstDist()) {
  1560. searchLevel(result_set, vec, otherChild, mindistsq, dists, epsError);
  1561. }
  1562. dists[idx] = dst;
  1563. }
  1564. public:
  1565. /** Stores the index in a binary file.
  1566. * IMPORTANT NOTE: The set of data points is NOT stored in the file, so when
  1567. * loading the index object it must be constructed associated to the same
  1568. * source of data points used while building it. See the example:
  1569. * examples/saveload_example.cpp \sa loadIndex */
  1570. void saveIndex(FILE *stream) { this->saveIndex_(*this, stream); }
  1571. /** Loads a previous index from a binary file.
  1572. * IMPORTANT NOTE: The set of data points is NOT stored in the file, so the
  1573. * index object must be constructed associated to the same source of data
  1574. * points used while building the index. See the example:
  1575. * examples/saveload_example.cpp \sa loadIndex */
  1576. void loadIndex(FILE *stream) { this->loadIndex_(*this, stream); }
  1577. };
  1578. /** kd-tree dynaimic index
  1579. *
  1580. * class to create multiple static index and merge their results to behave as
  1581. * single dynamic index as proposed in Logarithmic Approach.
  1582. *
  1583. * Example of usage:
  1584. * examples/dynamic_pointcloud_example.cpp
  1585. *
  1586. * \tparam DatasetAdaptor The user-provided adaptor (see comments above).
  1587. * \tparam Distance The distance metric to use: nanoflann::metric_L1,
  1588. * nanoflann::metric_L2, nanoflann::metric_L2_Simple, etc. \tparam DIM
  1589. * Dimensionality of data points (e.g. 3 for 3D points) \tparam IndexType Will
  1590. * be typically size_t or int
  1591. */
  1592. template <typename Distance, class DatasetAdaptor, int DIM = -1,
  1593. typename IndexType = size_t>
  1594. class KDTreeSingleIndexDynamicAdaptor {
  1595. public:
  1596. typedef typename Distance::ElementType ElementType;
  1597. typedef typename Distance::DistanceType DistanceType;
  1598. protected:
  1599. size_t m_leaf_max_size;
  1600. size_t treeCount;
  1601. size_t pointCount;
  1602. /**
  1603. * The dataset used by this index
  1604. */
  1605. const DatasetAdaptor &dataset; //!< The source of our data
  1606. std::vector<int> treeIndex; //!< treeIndex[idx] is the index of tree in which
  1607. //!< point at idx is stored. treeIndex[idx]=-1
  1608. //!< means that point has been removed.
  1609. KDTreeSingleIndexAdaptorParams index_params;
  1610. int dim; //!< Dimensionality of each data point
  1611. typedef KDTreeSingleIndexDynamicAdaptor_<Distance, DatasetAdaptor, DIM>
  1612. index_container_t;
  1613. std::vector<index_container_t> index;
  1614. public:
  1615. /** Get a const ref to the internal list of indices; the number of indices is
  1616. * adapted dynamically as the dataset grows in size. */
  1617. const std::vector<index_container_t> &getAllIndices() const { return index; }
  1618. private:
  1619. /** finds position of least significant unset bit */
  1620. int First0Bit(IndexType num) {
  1621. int pos = 0;
  1622. while (num & 1) {
  1623. num = num >> 1;
  1624. pos++;
  1625. }
  1626. return pos;
  1627. }
  1628. /** Creates multiple empty trees to handle dynamic support */
  1629. void init() {
  1630. typedef KDTreeSingleIndexDynamicAdaptor_<Distance, DatasetAdaptor, DIM>
  1631. my_kd_tree_t;
  1632. std::vector<my_kd_tree_t> index_(
  1633. treeCount, my_kd_tree_t(dim /*dim*/, dataset, treeIndex, index_params));
  1634. index = index_;
  1635. }
  1636. public:
  1637. Distance distance;
  1638. /**
  1639. * KDTree constructor
  1640. *
  1641. * Refer to docs in README.md or online in
  1642. * https://github.com/jlblancoc/nanoflann
  1643. *
  1644. * The KD-Tree point dimension (the length of each point in the datase, e.g. 3
  1645. * for 3D points) is determined by means of:
  1646. * - The \a DIM template parameter if >0 (highest priority)
  1647. * - Otherwise, the \a dimensionality parameter of this constructor.
  1648. *
  1649. * @param inputData Dataset with the input features
  1650. * @param params Basically, the maximum leaf node size
  1651. */
  1652. KDTreeSingleIndexDynamicAdaptor(const int dimensionality,
  1653. const DatasetAdaptor &inputData,
  1654. const KDTreeSingleIndexAdaptorParams &params =
  1655. KDTreeSingleIndexAdaptorParams(),
  1656. const size_t maximumPointCount = 1000000000U)
  1657. : dataset(inputData), index_params(params), distance(inputData) {
  1658. treeCount = static_cast<size_t>(std::log2(maximumPointCount));
  1659. pointCount = 0U;
  1660. dim = dimensionality;
  1661. treeIndex.clear();
  1662. if (DIM > 0)
  1663. dim = DIM;
  1664. m_leaf_max_size = params.leaf_max_size;
  1665. init();
  1666. const size_t num_initial_points = dataset.kdtree_get_point_count();
  1667. if (num_initial_points > 0) {
  1668. addPoints(0, num_initial_points - 1);
  1669. }
  1670. }
  1671. /** Deleted copy constructor*/
  1672. KDTreeSingleIndexDynamicAdaptor(
  1673. const KDTreeSingleIndexDynamicAdaptor<Distance, DatasetAdaptor, DIM,
  1674. IndexType> &) = delete;
  1675. /** Add points to the set, Inserts all points from [start, end] */
  1676. void addPoints(IndexType start, IndexType end) {
  1677. size_t count = end - start + 1;
  1678. treeIndex.resize(treeIndex.size() + count);
  1679. for (IndexType idx = start; idx <= end; idx++) {
  1680. int pos = First0Bit(pointCount);
  1681. index[pos].vind.clear();
  1682. treeIndex[pointCount] = pos;
  1683. for (int i = 0; i < pos; i++) {
  1684. for (int j = 0; j < static_cast<int>(index[i].vind.size()); j++) {
  1685. index[pos].vind.push_back(index[i].vind[j]);
  1686. if (treeIndex[index[i].vind[j]] != -1)
  1687. treeIndex[index[i].vind[j]] = pos;
  1688. }
  1689. index[i].vind.clear();
  1690. index[i].freeIndex(index[i]);
  1691. }
  1692. index[pos].vind.push_back(idx);
  1693. index[pos].buildIndex();
  1694. pointCount++;
  1695. }
  1696. }
  1697. /** Remove a point from the set (Lazy Deletion) */
  1698. void removePoint(size_t idx) {
  1699. if (idx >= pointCount)
  1700. return;
  1701. treeIndex[idx] = -1;
  1702. }
  1703. /**
  1704. * Find set of nearest neighbors to vec[0:dim-1]. Their indices are stored
  1705. * inside the result object.
  1706. *
  1707. * Params:
  1708. * result = the result object in which the indices of the
  1709. * nearest-neighbors are stored vec = the vector for which to search the
  1710. * nearest neighbors
  1711. *
  1712. * \tparam RESULTSET Should be any ResultSet<DistanceType>
  1713. * \return True if the requested neighbors could be found.
  1714. * \sa knnSearch, radiusSearch
  1715. */
  1716. template <typename RESULTSET>
  1717. bool findNeighbors(RESULTSET &result, const ElementType *vec,
  1718. const SearchParams &searchParams) const {
  1719. for (size_t i = 0; i < treeCount; i++) {
  1720. index[i].findNeighbors(result, &vec[0], searchParams);
  1721. }
  1722. return result.full();
  1723. }
  1724. };
  1725. /** An L2-metric KD-tree adaptor for working with data directly stored in an
  1726. * Eigen Matrix, without duplicating the data storage. You can select whether a
  1727. * row or column in the matrix represents a point in the state space.
  1728. *
  1729. * Example of usage:
  1730. * \code
  1731. * Eigen::Matrix<num_t,Dynamic,Dynamic> mat;
  1732. * // Fill out "mat"...
  1733. *
  1734. * typedef KDTreeEigenMatrixAdaptor< Eigen::Matrix<num_t,Dynamic,Dynamic> >
  1735. * my_kd_tree_t; const int max_leaf = 10; my_kd_tree_t mat_index(mat, max_leaf
  1736. * ); mat_index.index->buildIndex(); mat_index.index->... \endcode
  1737. *
  1738. * \tparam DIM If set to >0, it specifies a compile-time fixed dimensionality
  1739. * for the points in the data set, allowing more compiler optimizations. \tparam
  1740. * Distance The distance metric to use: nanoflann::metric_L1,
  1741. * nanoflann::metric_L2, nanoflann::metric_L2_Simple, etc. \tparam row_major
  1742. * If set to true the rows of the matrix are used as the points, if set to false
  1743. * the columns of the matrix are used as the points.
  1744. */
  1745. template <class MatrixType, int DIM = -1, class Distance = nanoflann::metric_L2,
  1746. bool row_major = true>
  1747. struct KDTreeEigenMatrixAdaptor {
  1748. typedef KDTreeEigenMatrixAdaptor<MatrixType, DIM, Distance, row_major> self_t;
  1749. typedef typename MatrixType::Scalar num_t;
  1750. typedef typename MatrixType::Index IndexType;
  1751. typedef
  1752. typename Distance::template traits<num_t, self_t>::distance_t metric_t;
  1753. typedef KDTreeSingleIndexAdaptor<metric_t, self_t,
  1754. MatrixType::ColsAtCompileTime, IndexType>
  1755. index_t;
  1756. index_t *index; //! The kd-tree index for the user to call its methods as
  1757. //! usual with any other FLANN index.
  1758. /// Constructor: takes a const ref to the matrix object with the data points
  1759. KDTreeEigenMatrixAdaptor(const size_t dimensionality,
  1760. const std::reference_wrapper<const MatrixType> &mat,
  1761. const int leaf_max_size = 10)
  1762. : m_data_matrix(mat) {
  1763. const auto dims = row_major ? mat.get().cols() : mat.get().rows();
  1764. if (size_t(dims) != dimensionality)
  1765. throw std::runtime_error(
  1766. "Error: 'dimensionality' must match column count in data matrix");
  1767. if (DIM > 0 && int(dims) != DIM)
  1768. throw std::runtime_error(
  1769. "Data set dimensionality does not match the 'DIM' template argument");
  1770. index =
  1771. new index_t(static_cast<int>(dims), *this /* adaptor */,
  1772. nanoflann::KDTreeSingleIndexAdaptorParams(leaf_max_size));
  1773. index->buildIndex();
  1774. }
  1775. public:
  1776. /** Deleted copy constructor */
  1777. KDTreeEigenMatrixAdaptor(const self_t &) = delete;
  1778. ~KDTreeEigenMatrixAdaptor() { delete index; }
  1779. const std::reference_wrapper<const MatrixType> m_data_matrix;
  1780. /** Query for the \a num_closest closest points to a given point (entered as
  1781. * query_point[0:dim-1]). Note that this is a short-cut method for
  1782. * index->findNeighbors(). The user can also call index->... methods as
  1783. * desired. \note nChecks_IGNORED is ignored but kept for compatibility with
  1784. * the original FLANN interface.
  1785. */
  1786. inline void query(const num_t *query_point, const size_t num_closest,
  1787. IndexType *out_indices, num_t *out_distances_sq,
  1788. const int /* nChecks_IGNORED */ = 10) const {
  1789. nanoflann::KNNResultSet<num_t, IndexType> resultSet(num_closest);
  1790. resultSet.init(out_indices, out_distances_sq);
  1791. index->findNeighbors(resultSet, query_point, nanoflann::SearchParams());
  1792. }
  1793. /** @name Interface expected by KDTreeSingleIndexAdaptor
  1794. * @{ */
  1795. const self_t &derived() const { return *this; }
  1796. self_t &derived() { return *this; }
  1797. // Must return the number of data points
  1798. inline size_t kdtree_get_point_count() const {
  1799. if(row_major)
  1800. return m_data_matrix.get().rows();
  1801. else
  1802. return m_data_matrix.get().cols();
  1803. }
  1804. // Returns the dim'th component of the idx'th point in the class:
  1805. inline num_t kdtree_get_pt(const IndexType idx, size_t dim) const {
  1806. if(row_major)
  1807. return m_data_matrix.get().coeff(idx, IndexType(dim));
  1808. else
  1809. return m_data_matrix.get().coeff(IndexType(dim), idx);
  1810. }
  1811. // Optional bounding-box computation: return false to default to a standard
  1812. // bbox computation loop.
  1813. // Return true if the BBOX was already computed by the class and returned in
  1814. // "bb" so it can be avoided to redo it again. Look at bb.size() to find out
  1815. // the expected dimensionality (e.g. 2 or 3 for point clouds)
  1816. template <class BBOX> bool kdtree_get_bbox(BBOX & /*bb*/) const {
  1817. return false;
  1818. }
  1819. /** @} */
  1820. }; // end of KDTreeEigenMatrixAdaptor
  1821. /** @} */
  1822. /** @} */ // end of grouping
  1823. } // namespace nanoflann
  1824. #endif /* NANOFLANN_HPP_ */