Skip to content

Commit

Permalink
Merge pull request #35 from Jaybro/ctad
Browse files Browse the repository at this point in the history
Ctad
  • Loading branch information
Jaybro authored Sep 26, 2023
2 parents 46699e6 + 35b5fbd commit f6f65d0
Show file tree
Hide file tree
Showing 17 changed files with 193 additions and 70 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ include(${CMAKE_CURRENT_SOURCE_DIR}/cmake/utils.cmake)

project(pico_tree
LANGUAGES CXX
VERSION 0.8.2
VERSION 0.8.3
DESCRIPTION "PicoTree is a C++ header only library for fast nearest neighbor searches and range searches using a KdTree."
HOMEPAGE_URL "https://github.com/Jaybro/pico_tree")

Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ PicoTree is a C++ header only library with [Python bindings](https://github.com/
| [Scikit-learn KDTree][skkd] 1.2.2 | ... | 6.2s | ... | 42.2s |
| [pykdtree][pykd] 1.3.7 | ... | 1.0s | ... | 6.6s |
| [OpenCV FLANN][cvfn] 4.6.0 | 1.9s | ... | 4.7s | ... |
| PicoTree KdTree v0.8.2 | 0.9s | 1.0s | 2.8s | 3.1s |
| PicoTree KdTree v0.8.3 | 0.9s | 1.0s | 2.8s | 3.1s |

Two [LiDAR](./docs/benchmark.md) based point clouds of sizes 7733372 and 7200863 were used to generate these numbers. The first point cloud was the input to the build algorithm and the second to the query algorithm. All benchmarks were run on a single thread with the following parameters: `max_leaf_size=10` and `knn=1`. A more detailed [C++ comparison](./docs/benchmark.md) of PicoTree is available with respect to [nanoflann][nano].

Expand Down
2 changes: 1 addition & 1 deletion docs/benchmark.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ One of the PicoTree examples contains [benchmarks](../examples/benchmark/) of di

The results described in this document were generated on 29-08-2021 using MinGW GCC 10.3, PicoTree v0.7.4 and Nanoflann v1.3.2.

Note: The performance of PicoTree v0.8.2 released on 07-09-2023 is identical to that of v0.7.4. However, the build algorithm of nanoflann v1.5.0 regressed and has become 90% slower.
Note: The performance of PicoTree v0.8.3 released on 26-09-2023 is identical to that of v0.7.4. However, the build algorithm of nanoflann v1.5.0 regressed and has become 90% slower.

# Data sets

Expand Down
7 changes: 3 additions & 4 deletions examples/eigen/eigen.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,13 +40,12 @@ std::vector<PointX> GenerateRandomEigenN(
// neighbors.
void BasicVector() {
using PointX = Eigen::Vector2f;
using KdTree = pico_tree::KdTree<std::vector<PointX>>;
using Scalar = typename KdTree::ScalarType;
using Index = typename KdTree::IndexType;
using Scalar = typename PointX::Scalar;
using Index = int;

// Including <pico_tree/eigen3_traits.hpp> provides support for Eigen types
// with std::vector.
pico_tree::KdTree<std::vector<PointX>> tree(
pico_tree::KdTree tree(
GenerateRandomEigenN<PointX>(kNumPoints, kArea), kMaxLeafCount);

PointX p = PointX::Random() * kArea / Scalar(2.0);
Expand Down
94 changes: 67 additions & 27 deletions examples/kd_tree/kd_tree_creation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,28 @@
#include <pico_tree/kd_tree.hpp>
#include <pico_tree/vector_traits.hpp>

// This application demonstrates how a KdTree can take its input point set.
// Although all of the examples use an std::vector<> as the input for building a
// KdTree, they will work with any of the inputs supported by this library
// (e.g., Eigen::Matrix<>).
// The examples in this application demonstrate the different ways in which a
// KdTree can be constructed from a point set. The following is covered:
//
// Value-move idiom:
// A KdTree takes the input by value. This means that the KdTree takes ownership
// of a copy of the input. When a copy is not desired, the point set can either
// be moved into the KdTree or it can take the point set by reference by
// wrapping it in an std::reference_wrapper<>. In the latter case, the KdTree
// will only have shallow ownership of the input. This allows it to be used for
// other purposes as well.
//
// Class template argument deduction:
// The class template argument that defines the space type (the input point set
// type) does not always have to be specified and can be deduced by the
// compiler. In case another class template argument needs to be specified, such
// as the metric type, then the space type may still be deduced using the
// MakeKdTree<> convenience method.

// Although all of the examples use an std::vector<std::array<>> as the input
// for building a KdTree, they will work with any of the inputs supported by
// this library (e.g., Eigen::Matrix<>).
using Space = std::vector<std::array<float, 3>>;

template <typename Tree>
void QueryTree(Tree const& tree) {
Expand All @@ -17,61 +35,83 @@ void QueryTree(Tree const& tree) {
std::cout << "Index closest point: " << nn.index << std::endl;
}

auto MakePointSet() {
std::vector<std::array<float, 3>> points{
{0.0f, 1.0f, 2.0f}, {3.0f, 4.0f, 5.0f}};
auto MakePointSet() { return Space{{0.0f, 1.0f, 2.0f}, {3.0f, 4.0f, 5.0f}}; }

return points;
}

// The KdTree takes the input by value. In this example, creating a KdTree
// results in a copy of the input point set.
// In this example, the creation of a KdTree results in a copy of the input
// point set. The KdTree has full ownership of the copy.
void BuildKdTreeWithCopy() {
int max_leaf_size = 12;
auto points = MakePointSet();

pico_tree::KdTree<std::vector<std::array<float, 3>>> tree(
points, max_leaf_size);
pico_tree::KdTree<Space> tree(points, max_leaf_size);

QueryTree(tree);
}

// The KdTree takes the input by value. In this example, the point sets are not
// copied but moved into the KdTree. This prevents a copy.
// In this example, the point sets are not copied but moved into the KdTrees
// when they are created. Each tree has full ownership of the moved point set.
void BuildKdTreeWithMove() {
int max_leaf_size = 12;
auto points = MakePointSet();

pico_tree::KdTree<std::vector<std::array<float, 3>>> tree1(
std::move(points), max_leaf_size);
pico_tree::KdTree<Space> tree1(std::move(points), max_leaf_size);

pico_tree::KdTree<std::vector<std::array<float, 3>>> tree2(
MakePointSet(), max_leaf_size);
pico_tree::KdTree<Space> tree2(MakePointSet(), max_leaf_size);

QueryTree(tree1);
QueryTree(tree2);
}

// The KdTree takes the input by value. In this example, the input is taken by
// reference. This prevents a copy.
// In this example, the input is wrapped in an std::reference_wrapper<>. Thus,
// only a reference is copied by a KdTree. Each tree only has shallow ownership
// of the input point set.
void BuildKdTreeWithReference() {
int max_leaf_size = 12;
auto points = MakePointSet();

// By reference.
pico_tree::KdTree<std::reference_wrapper<std::vector<std::array<float, 3>>>>
tree1(points, max_leaf_size);
pico_tree::KdTree<std::reference_wrapper<Space>> tree1(points, max_leaf_size);

// By const reference.
pico_tree::KdTree<
std::reference_wrapper<std::vector<std::array<float, 3>> const>>
tree2(points, max_leaf_size);
pico_tree::KdTree<std::reference_wrapper<Space const>> tree2(
points, max_leaf_size);

QueryTree(tree1);
QueryTree(tree2);
}

// This example shows that the type of the input point set may be deduced by the
// compiler.
void SpaceTypeDeduction() {
int max_leaf_size = 12;
auto points = MakePointSet();

// The type of the first class template argument, the space type, is
// determined by the compiler.
pico_tree::KdTree tree1(std::ref(points), max_leaf_size);

using KdTree1Type = pico_tree::KdTree<std::reference_wrapper<Space>>;

static_assert(std::is_same_v<decltype(tree1), KdTree1Type>);

// Using the previous auto deduction method, we still have to specify the
// space type when we want to change any of the other template arguments, such
// as the metric type. In this case we can use the MakeKdTree method to make
// life a bit easier.
auto tree2 =
pico_tree::MakeKdTree<pico_tree::LInf>(std::ref(points), max_leaf_size);

using KdTree2Type =
pico_tree::KdTree<std::reference_wrapper<Space>, pico_tree::LInf>;

static_assert(std::is_same_v<decltype(tree2), KdTree2Type>);

QueryTree(tree1);
QueryTree(tree2);
}

int main() {
SpaceTypeDeduction();
BuildKdTreeWithReference();
BuildKdTreeWithMove();
BuildKdTreeWithCopy();
Expand Down
11 changes: 7 additions & 4 deletions examples/kd_tree/kd_tree_minimal.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
#include <iostream>
// Provides support for fixed size arrays and std::array.
#include <pico_tree/array_traits.hpp>
#include <pico_tree/kd_tree.hpp>
// Provides support for std::vector.
#include <pico_tree/vector_traits.hpp>

// This example shows how to create and query a KdTree. An std::vector can be
Expand All @@ -11,10 +13,11 @@ int main() {
std::vector<std::array<float, 3>> points{
{0.0f, 1.0f, 2.0f}, {3.0f, 4.0f, 5.0f}};

// The KdTree takes the input by value. To prevent a copy, we can either use
// an std::reference_wrapper or move the point set into the tree.
pico_tree::KdTree<std::reference_wrapper<std::vector<std::array<float, 3>>>>
tree(points, max_leaf_size);
// The KdTree takes the input by value. To prevent a copy, we can either move
// the point set into the tree or the point set can be taken by reference by
// wrapping it in an std::reference_wrapper. Below we take the input by
// reference:
pico_tree::KdTree tree(std::ref(points), max_leaf_size);

float query[3] = {4.0f, 4.0f, 4.0f};
pico_tree::Neighbor<int, float> nn;
Expand Down
3 changes: 1 addition & 2 deletions examples/opencv/opencv.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,7 @@ void BasicVector() {
using PointX = cv::Vec<Scalar, 3>;
std::vector<PointX> random = GenerateRandomVecN<PointX>(kNumPoints, kArea);

pico_tree::KdTree<std::reference_wrapper<std::vector<PointX>>> tree(
random, 10);
pico_tree::KdTree tree(std::cref(random), 10);

auto p = random[random.size() / 2];

Expand Down
4 changes: 4 additions & 0 deletions examples/pico_understory/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,10 @@ target_sources(pico_understory
${CMAKE_CURRENT_LIST_DIR}/pico_understory/internal/cover_tree_node.hpp
${CMAKE_CURRENT_LIST_DIR}/pico_understory/internal/cover_tree_search.hpp
${CMAKE_CURRENT_LIST_DIR}/pico_understory/internal/kd_tree_priority_search.hpp
${CMAKE_CURRENT_LIST_DIR}/pico_understory/internal/matrix_space_traits.hpp
${CMAKE_CURRENT_LIST_DIR}/pico_understory/internal/matrix_space.hpp
${CMAKE_CURRENT_LIST_DIR}/pico_understory/internal/point_traits.hpp
${CMAKE_CURRENT_LIST_DIR}/pico_understory/internal/priority_queue.hpp
${CMAKE_CURRENT_LIST_DIR}/pico_understory/internal/rkd_tree_builder.hpp
${CMAKE_CURRENT_LIST_DIR}/pico_understory/internal/rkd_tree_hh_data.hpp
${CMAKE_CURRENT_LIST_DIR}/pico_understory/internal/static_buffer.hpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include "pico_tree/internal/kd_tree_node.hpp"
#include "pico_tree/internal/point.hpp"
#include "pico_tree/metric.hpp"
#include "pico_understory/internal/priority_queue.hpp"

namespace pico_tree::internal {

Expand Down Expand Up @@ -48,40 +49,24 @@ class PrioritySearchNearestEuclidean {
inline void operator()(NodeType const* const root_node) {
std::size_t leaves_visited = 0;
queue_.reserve(max_leaves_visited_);
queue_.push_back({ScalarType(0.0), root_node});
queue_.PushBack(ScalarType(0.0), root_node);
while (!queue_.empty()) {
auto const [node_box_distance, node] = queue_.front();
auto const [node_box_distance, node] = queue_.Front();

if (leaves_visited >= max_leaves_visited_ ||
visitor_.max() < node_box_distance) {
break;
}

// TODO For small queues it's probably not worth it to use a deque.
queue_.erase(queue_.begin());
queue_.PopFront();

SearchNearest(node, node_box_distance);
++leaves_visited;
queue_.reserve(max_leaves_visited_ - leaves_visited);
}
}

private:
inline void Push(NodeType const* node, ScalarType node_box_distance) {
if (queue_.size() < max_leaves_visited_) {
if (queue_.empty()) {
queue_.push_back({node_box_distance, node});
} else if (queue_.back().first < node_box_distance) {
queue_.push_back({node_box_distance, node});
} else {
queue_.push_back(queue_.back());
InsertSorted(
queue_.begin(), std::prev(queue_.end()), {node_box_distance, node});
}
} else if (queue_.back().first > node_box_distance) {
InsertSorted(queue_.begin(), queue_.end(), {node_box_distance, node});
}
}

// Add nodes to the priority queue until a leaf node is reached.
inline void SearchNearest(
NodeType const* const node, ScalarType node_box_distance) {
Expand Down Expand Up @@ -139,7 +124,7 @@ class PrioritySearchNearestEuclidean {

// Add to priority queue to be searched later.
if (visitor_.max() > node_box_distance) {
Push(node_2nd, node_box_distance);
queue_.PushBack(node_box_distance, node_2nd);
}
}
}
Expand All @@ -151,7 +136,7 @@ class PrioritySearchNearestEuclidean {
Size max_leaves_visited_;
// TODO This gets created every query. Solving this would require a different
// PicoTree interface. The queue probably shouldn't be too big.
std::vector<QueuePairType> queue_;
PriorityQueue<ScalarType, NodeType const*> queue_;
Visitor_& visitor_;
};

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
#pragma once

#include <vector>

#include "pico_tree/internal/search_visitor.hpp"

namespace pico_tree::internal {

template <typename P_, typename T_>
class PriorityQueue {
public:
inline explicit PriorityQueue() = default;

inline std::pair<P_, T_>& Front() { return buffer_.front(); }

inline std::pair<P_, T_> const& Front() const { return buffer_.front(); }

inline void PopFront() {
// TODO For small queues it's probably not worth it to use a deque.
buffer_.erase(buffer_.begin());
}

inline void PushBack(P_ priority, T_ item) {
if (buffer_.size() < buffer_.capacity()) {
if (buffer_.empty()) {
buffer_.push_back({priority, item});
} else if (buffer_.back().first < priority) {
buffer_.push_back({priority, item});
} else {
buffer_.push_back(buffer_.back());
InsertSorted(
buffer_.begin(), std::prev(buffer_.end()), {priority, item});
}
} else if (buffer_.back().first > priority) {
InsertSorted(buffer_.begin(), buffer_.end(), {priority, item});
}
}

void reserve(std::size_t capacity) { buffer_.reserve(capacity); }

std::size_t capacity() const { return buffer_.capacity(); }

std::size_t size() const { return buffer_.size(); }

bool empty() const { return buffer_.empty(); }

private:
std::vector<std::pair<P_, T_>> buffer_;
};

} // namespace pico_tree::internal
14 changes: 14 additions & 0 deletions examples/pico_understory/pico_understory/kd_forest.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,4 +116,18 @@ class KdForest {
std::vector<RKdTreeDataType> data_;
};

template <typename Space_>
KdForest(Space_, Size)
-> KdForest<Space_, L2Squared, SplittingRule::kSlidingMidpoint, int>;

template <
typename Metric_ = L2Squared,
SplittingRule SplittingRule_ = SplittingRule::kSlidingMidpoint,
typename Index_ = int,
typename Space_>
auto MakeKdForest(Space_&& space, Size max_leaf_size, Size forest_size) {
return KdForest<std::decay_t<Space_>, Metric_, SplittingRule_, Index_>(
std::forward<Space_>(space), max_leaf_size, forest_size);
}

} // namespace pico_tree
2 changes: 1 addition & 1 deletion setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

setup(name='pico_tree',
# The same as the CMake project version.
version='0.8.2',
version='0.8.3',
description='PicoTree Python Bindings',
author='Jonathan Broere',
url='https://github.com/Jaybro/pico_tree',
Expand Down
Loading

0 comments on commit f6f65d0

Please sign in to comment.