UNC-Robotics / nigh

Concurrent exact nearest neighbor searching in robotics-relevant spaces, including Euclidean, SO(3), SE(3) and weighted combinations thereof
BSD 3-Clause "New" or "Revised" License
54 stars 12 forks source link

Using std::vector #4

Closed velecto1 closed 1 year ago

velecto1 commented 1 year ago

Hello,

I would like to use this library with std::vector as the key type. The website https://robotics.cs.unc.edu/nigh/ claims that std::vector can be used "out of the box". However, the following code does not work for me,

#include "nigh/lp_space.hpp"
#include "nigh/kdtree_median.hpp"
#include "nigh/gnat.hpp"
#include "nigh/kdtree_batch.hpp"
#include "nigh/linear.hpp"
#include "nigh/metric/space_lp_vector.hpp"

struct Node {
    std::vector<double> key_;
    std::string data_;
};

struct KeyFn {
    const std::vector<double> &operator()(const Node &n) const {
      return n.key_;
    }
};

void nigh_main() {
  namespace nigh = unc::robotics::nigh;

  // using Space = nigh::L2Space<double, 3>;
  // using Space = nigh::L2Space<std::vector<double>, 3>;
  using Space = nigh::metric::Space<std::vector<double>, nigh::metric::LP<2>>;

  nigh::Nigh<Node, Space, KeyFn, nigh::Concurrent, nigh::KDTreeBatch<>> nn;
}

giving this error:

/home/tomtom/measuring_time/nigh/src/nigh/kdtree_batch.hpp: In constructor ‘unc::robotics::nigh::Nigh<T, Space_, KeyFn_, Concurrency_, unc::robotics::nigh::KDTreeBatch<batchSize>, Allocator_>::Nigh(const Space&, const KeyFn&, Allocator) [with T = Node; Space = unc::robotics::nigh::metric::Space<std::vector<double>, unc::robotics::nigh::metric::LP<2> >; KeyFn = KeyFn; Concurrency = unc::robotics::nigh::Concurrent; long unsigned int batchSize = 8; Allocator = std::allocator<Node>]’:
/home/tomtom/measuring_time/nigh/src/nigh/kdtree_batch.hpp:99:35: error: use of deleted function ‘unc::robotics::nigh::metric::Space<std::vector<double>, unc::robotics::nigh::metric::LP<2> >::Space()’
   99 |             const Space& metric = Space(),
      |                                   ^~~~~~~

I know how to make it work for a fixed vector length using the code from custom_vector_demo.cpp, but that is not "out of the box" in my eyes. What is the correct way, please?

Moreover, I would like to have a variable length of my feature vector based on the arguments from a command line. Is there a way to achieve this with Nigh?

Even if I want to rework the structure from custom_vector_demo.cpp, I don't know how. Two elements state the size of the vector. One explicitly says that it can be set to -1 for types of arbitrary dimensions:

        // Declare the dimensions of Vec3 as a constant.  For
        // customizing types that can be of arbitrary dimensions,
        // kDimensions can be set to -1.
        static constexpr int kDimensions = 3;

But then there is the second element which cannot return just "-1". Returning a constexpr and not having any input argument, I guess it has to be hardcoded anyway?

        // This constexpr method should return the number of
        // dimensions of the vector.  This method should match
        // kDimensions, except in the case where kDimensions is -1.
        // Note kDimensions is signed, while dimensions() is unsigned.
        constexpr unsigned dimensions() const {
            return 3;
        }
velecto1 commented 1 year ago

Okay, I got it; a colleague has helped me. The solution is to pass the Space not as a type but also as an object, like this:

  using Space = nigh::metric::Space<std::vector<double>, nigh::metric::LP<2>>;

  Space s(3);

  nigh::Nigh<Node, Space, KeyFn, nigh::Concurrent, nigh::KDTreeBatch<>> nn{s};

Explanation: To create an object of type nigh::Nigh, this constructor for NearestBase is used:

        NearestBase(
            const Space& metricSpace = Space(),
            const KeyFn& keyFn = KeyFn(),
            const Allocator& allocator = Allocator())
            : space_(metricSpace)
            , keyFn_(keyFn)
            , allocator_(allocator)
        {
        }

By default, it creates the metricSpace using a constructor Space() with no arguments. However, the constructor of SpaceBase<Dynamic> requires an argument:

        explicit SpaceBase(unsigned dimensions)
            : dimensions_(dimensions) {
          // dimensions must be positive
          assert(dimensions > 0);

          // something likely went wrong if dimensions is this big...
          assert(dimensions < static_cast<unsigned>(std::numeric_limits<int>::max()));
        }

The solution creates a Space object with the correct dimensions by calling the constructor SpaceBase(unsigned dimensions) and passes the Space object to the constructor of NearestBase, replacing the one of its default arguments which was unconstructable.