The most up-to-date version of this page will be always available at: http://code.google.com/p/nanoflann/


1. About


nanoflann is a C++ header-only library for building KD-Trees, mostly optimized for 2D or 3D point clouds. Queries for neighbors around any arbitrary location in space can then be solved quickly and efficiently using Approximate Nearest Neighbor (ANN) algorithms.

nanoflann does not require compiling or installing, just an #include <nanoflann.hpp> in your code.

This library is a fork (and a subset) of the `flann` library, by Marius Muja and David G. Lowe, born as a child project of MRPT. Following the original license terms, nanoflann is distributed under the BSD license. If you want to contact me for reporting any issue or patch, write to joseluisblancoc@gmail.com

1.1. Obtaining the code

1.2. C++ API reference

1.3. Why a fork?

Refer to the examples below or to the C++ API of nanoflann::KDTreeSingleIndexAdaptor<> for more info.

1.4. What can nanoflann do?

1.5. What can't nanoflann do?

1.6. Code examples



2. Any help choosing the KD-tree parameters?


2.1. KDTreeSingleIndexAdaptorParams::leaf_max_size

A KD-tree is... well, a tree :-). And as such it has a root node, a set of intermediary nodes and finally, "leaf" nodes which are those without children.

Points (or, properly, point indices) are only stored in leaf nodes. Each leaf contains a list of which points fall within its range.

While building the tree, nodes are recursively divided until the number of points inside is equal or below some threshold. That is leaf_max_size. While doing queries, the "tree algorithm" ends by selecting leaf nodes, then performing linear search (one-by-one) for the closest point to the query within all those in the leaf.

So, leaf_max_size must be set as a tradeoff:

What number to select really depends on the application and even on the size of the processor cache memory, so ideally you should do some benchmarking for maximizing efficiency.

But to help choosing a good value as a rule of thumb, I provide the following two benchmarks. Each graph represents the tree build (horizontal) and query (vertical) times for different leaf_max_size values between 1 and 10K (as 95% uncertainty ellipses, deformed due to the logarithmic scale).

So, it seems that a leaf_max_size between 10 and 50 would be optimum in applications where the cost of queries dominates (e.g. ICP). At present, its default value is 10.


2.2. KDTreeSingleIndexAdaptorParams::checks

This parameter is really ignored in nanoflann, but was kept for backward compatibility with the original FLANN interface. Just ignore it.



3. Performance


3.1. nanoflann: faster and less memory usage

Refer to the "Why a fork?" section above for the main optimization ideas behind nanoflann.

Notice that there are no explicit SSE2/SSE3 optimizations in nanoflann, but the intensive usage of inline and templates in practice turns into automatically SSE-optimized code generated by the compiler.

3.2. Benchmark: original flann vs nanoflann

The most time-consuming part of many point cloud algorithms (like ICP) is querying a KD-Tree for nearest neighbors. This operation is therefore the most time critical.

nanoflann provides a ~50% time saving with respect to the original flann implementation (times in this chart are in microseconds for each query):

Although most of the gain comes from the queries (due to the large number of them in any typical operation with point clouds), there is also some time saved while building the KD-tree index, due to the templatized-code but also for the avoidance of duplicating the data in an auxiliary matrix (times in the next chart are in milliseconds):

These performance tests are only orientative. If you want to repeat them, read the instructions in http://nanoflann.googlecode.com/svn/trunk/perf-tests/


4. Other KD-tree projects




Note: The project logo is due to CedarSeed