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

Define weights of ScaledSpace at runtime #2

Closed clemense closed 5 years ago

clemense commented 5 years ago

Is there any solution to select the weight of a ScaledSpace during runtime? (i.e. so3weight and l2weight for SE3Space)

jeffi commented 5 years ago

Yes, there is support for setting the weights at runtime. (It was incomplete when you wrote the ticket, but now is fully implemented). Probably the best place to get started is to look at the test cases for scaled spaces. But it essentially boils down to creating a CartesianSpace around ScaledSpace wrappers of SO3Space and L2Space.

    using namespace unc::robotics::nigh;
    using Space = CartesianSpace<
        ScaledSpace<SO3Space<double>>,
        ScaledSpace<L2Space<double, 3>>>;

Then you have to create a space object that you pass into Nigh's constructor.

    double so3wt = 12.345;
    double l2wt = 6.789;
    Space space(so3wt, l2wt);
    Nigh<..., Space, ...> nn(space);