Closed velecto1 closed 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.
Hello,
I would like to use this library with
std::vector
as the key type. The website https://robotics.cs.unc.edu/nigh/ claims thatstd::vector
can be used "out of the box". However, the following code does not work for me,giving this error:
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: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?