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

assert(dot <= 0) failed #3

Open barcode opened 5 years ago

barcode commented 5 years ago

I encountered a pretty similar issue to #1. I was able to narrow it down to eight elements (as soon as i remove any of those, the segfault does not occur ) and i am only using SO3.

Points (w, x, y, z):

0.662702f, 0.219097f, 0.211232f, 0.684254f
0.658478f, 0.256881f, 0.256784f, 0.659152f
0.658478f, 0.256881f, 0.256784f, 0.659152f
0.641592f, -0.290111f, 0.286126f, -0.649867f
0.644836f, -0.274049f, 0.267667f, -0.661391f
0.642503f, -0.279932f, 0.273478f, -0.658816f
0.642491f, -0.290219f, 0.287658f, -0.648252f
0.644836f, -0.27405f, 0.267667f, -0.661391f
0.642443f, -0.290327f, 0.287766f, -0.648203f

Example code: https://gist.github.com/barcode/f417a76916cbfe0582fccde9238f2971

I compile with

 /usr/bin/g++-8  -I/tmp/nigh/src -I/usr/include/eigen3  -g   -std=c++2a -o nigh_segfault.cpp.o -c nigh_segfault.cpp

Compiler version:

g++-8 (Ubuntu 8.3.0-6ubuntu1~18.04.1) 8.3.0
Copyright (C) 2018 Free Software Foundation, Inc.
This is free software; see the source for copying conditions.  There is NO
warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.

Error:

kdtree_batch/traversal_so3.hpp:171: unc::robotics::nigh::impl::kdtree_batch::Traversal<Tree, Key, unc::robotics::nigh::metric::SO3, Get>::Node* unc::robotics::nigh::impl::kdtree_batch::Traversal<Tree, Key, unc::robotics::nigh::metric::SO3, Get>::split(Tree&, const Space&, unc::robotics::nigh::impl::kdtree_batch::Traversal<Tree, Key, unc::robotics::nigh::metric::SO3, Get>::Leaf*, const Key&, unsigned int, Traversal&) [with Traversal = unc::robotics::nigh::impl::kdtree_batch::Traversal<unc::robotics::nigh::Nigh<long unsigned int, unc::robotics::nigh::metric::Space<Eigen::Quaternion<float>, unc::robotics::nigh::metric::SO3, void>, const test_ori()::<lambda(std::size_t)>, unc::robotics::nigh::NoThreadSafety, unc::robotics::nigh::KDTreeBatch<> >, Eigen::Quaternion<float>, unc::robotics::nigh::metric::SO3, unc::robotics::nigh::impl::RootGet>; Tree = unc::robotics::nigh::Nigh<long unsigned int, unc::robotics::nigh::metric::Space<Eigen::Quaternion<float>, unc::robotics::nigh::metric::SO3, void>, const test_ori()::<lambda(std::size_t)>, unc::robotics::nigh::NoThreadSafety, unc::robotics::nigh::KDTreeBatch<> >; Key = Eigen::Quaternion<float>; Get = unc::robotics::nigh::impl::RootGet; unc::robotics::nigh::impl::kdtree_batch::Traversal<Tree, Key, unc::robotics::nigh::metric::SO3, Get>::Node = unc::robotics::nigh::impl::kdtree_batch::Node<long unsigned int, unc::robotics::nigh::metric::Space<Eigen::Quaternion<float>, unc::robotics::nigh::metric::SO3, void>, unc::robotics::nigh::NoThreadSafety>; unc::robotics::nigh::impl::kdtree_batch::Traversal<Tree, Key, unc::robotics::nigh::metric::SO3, Get>::Space = unc::robotics::nigh::metric::Space<Eigen::Quaternion<float>, unc::robotics::nigh::metric::SO3, void>; unc::robotics::nigh::impl::kdtree_batch::Traversal<Tree, Key, unc::robotics::nigh::metric::SO3, Get>::Leaf = unc::robotics::nigh::impl::kdtree_batch::Leaf<long unsigned int, unc::robotics::nigh::metric::Space<Eigen::Quaternion<float>, unc::robotics::nigh::metric::SO3, void>, unc::robotics::nigh::NoThreadSafety, 8>]: Assertion `dot <= 0' failed.
Aborted (core dumped)