ipab-slmc / exotica

Extensible Optimization Framework
https://ipab-slmc.github.io/exotica
BSD 3-Clause "New" or "Revised" License
150 stars 70 forks source link

Collision scene with plane #449

Open christian-rauch opened 5 years ago

christian-rauch commented 5 years ago

EXOTica crashes when using a collision scene that contains a plane:

ompl.getProblem().getScene().addObjectToEnvironment(
    name="table_plane",
    shape=exo.Plane(0.0, 0.0, 1.0, 0.0),
    transform=exo.KDLFrame([0, 0, -0.5]))

Full example: example_attach_plane.py.txt (derived from example_attach_plane.py).

Backtrace:

Thread 1 "python" received signal SIGSEGV, Segmentation fault.
0x00007fffeae8bb6a in fcl::HierarchyTree<fcl::AABB>::bottomup(__gnu_cxx::__normal_iterator<fcl::NodeBase<fcl::AABB>**, std::vector<fcl::NodeBase<fcl::AABB>*, std::allocator<fcl::NodeBase<fcl::AABB>*> > >, __gnu_cxx::__normal_iterator<fcl::NodeBase<fcl::AABB>**, std::vector<fcl::NodeBase<fcl::AABB>*, std::allocator<fcl::NodeBase<fcl::AABB>*> > >) () from /usr/lib/x86_64-linux-gnu/libfcl.so.0.5
(gdb) bt
#0  0x00007fffeae8bb6a in fcl::HierarchyTree<fcl::AABB>::bottomup(__gnu_cxx::__normal_iterator<fcl::NodeBase<fcl::AABB>**, std::vector<fcl::NodeBase<fcl::AABB>*, std::allocator<fcl::NodeBase<fcl::AABB>*> > >, __gnu_cxx::__normal_iterator<fcl::NodeBase<fcl::AABB>**, std::vector<fcl::NodeBase<fcl::AABB>*, std::allocator<fcl::NodeBase<fcl::AABB>*> > >) () at /usr/lib/x86_64-linux-gnu/libfcl.so.0.5
#1  0x00007fffeae8cbbd in fcl::HierarchyTree<fcl::AABB>::topdown_0(__gnu_cxx::__normal_iterator<fcl::NodeBase<fcl::AABB>**, std::vector<fcl::NodeBase<fcl::AABB>*, std::allocator<fcl::NodeBase<fcl::AABB>*> > >, __gnu_cxx::__normal_iterator<fcl::NodeBase<fcl::AABB>**, std::vector<fcl::NodeBase<fcl::AABB>*, std::allocator<fcl::NodeBase<fcl::AABB>*> > >) () at /usr/lib/x86_64-linux-gnu/libfcl.so.0.5
#2  0x00007fffeae8cb68 in fcl::HierarchyTree<fcl::AABB>::topdown_0(__gnu_cxx::__normal_iterator<fcl::NodeBase<fcl::AABB>**, std::vector<fcl::NodeBase<fcl::AABB>*, std::allocator<fcl::NodeBase<fcl::AABB>*> > >, __gnu_cxx::__normal_iterator<fcl::NodeBase<fcl::AABB>**, std::vector<fcl::NodeBase<fcl::AABB>*, std::allocator<fcl::NodeBase<fcl::AABB>*> > >) () at /usr/lib/x86_64-linux-gnu/libfcl.so.0.5
#3  0x00007fffeae8cb7a in fcl::HierarchyTree<fcl::AABB>::topdown_0(__gnu_cxx::__normal_iterator<fcl::NodeBase<fcl::AABB>**, std::vector<fcl::NodeBase<fcl::AABB>*, std::allocator<fcl::NodeBase<fcl::AABB>*> > >, __gnu_cxx::__normal_iterator<fcl::NodeBase<fcl::AABB>**, std::vector<fcl::NodeBase<fcl::AABB>*, std::allocator<fcl::NodeBase<fcl::AABB>*> > >) () at /usr/lib/x86_64-linux-gnu/libfcl.so.0.5
#4  0x00007fffeae8cb68 in fcl::HierarchyTree<fcl::AABB>::topdown_0(__gnu_cxx::__normal_iterator<fcl::NodeBase<fcl::AABB>**, std::vector<fcl::NodeBase<fcl::AABB>*, std::allocator<fcl::NodeBase<fcl::AABB>*> > >, __gnu_cxx::__normal_iterator<fcl::NodeBase<fcl::AABB>**, std::vector<fcl::NodeBase<fcl::AABB>*, std::allocator<fcl::NodeBase<fcl::AABB>*> > >) () at /usr/lib/x86_64-linux-gnu/libfcl.so.0.5
#5  0x00007fffeae8ce11 in fcl::HierarchyTree<fcl::AABB>::init_0(std::vector<fcl::NodeBase<fcl::AABB>*, std::allocator<fcl::NodeBase<fcl::AABB>*> >&) () at /usr/lib/x86_64-linux-gnu/libfcl.so.0.5
#6  0x00007fffeae8a085 in fcl::DynamicAABBTreeCollisionManager::registerObjects(std::vector<fcl::CollisionObject*, std::allocator<fcl::CollisionObject*> > const&) () at /usr/lib/x86_64-linux-gnu/libfcl.so.0.5
#7  0x00007fff965f142c in exotica::CollisionSceneFCL::isStateValid(bool, double) () at /home/christian/Development/mpe_io_ws/devel/lib//libexotica_collision_scene_fcl.so
#8  0x00007fffc9633eb9 in exotica::CollisionCheck::update(Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1> const, 0, Eigen::InnerStride<1> > const&, Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1>, 0, Eigen::InnerStride<1> >) () at /home/christian/Development/mpe_io_ws/devel/lib//libtask_map.so
#9  0x00007ffff58d2b6c in exotica::SamplingProblem::isValid(Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1> const, 0, Eigen::InnerStride<1> > const&) ()
    at /home/christian/Development/mpe_io_ws/devel/lib/libexotica.so
#10 0x00007fffcae831fc in exotica::OMPLStateValidityChecker::isValid(ompl::base::State const*, double&) const () at /home/christian/Development/mpe_io_ws/devel/lib//libexotica_ompl_solver.so
#11 0x00007fffcae822ed in exotica::OMPLStateValidityChecker::isValid(ompl::base::State const*) const () at /home/christian/Development/mpe_io_ws/devel/lib//libexotica_ompl_solver.so
#12 0x00007fffcae9a664 in exotica::OMPLSolver<exotica::SamplingProblem>::SetGoalState(Eigen::Ref<Eigen::Matrix<double, -1, 1, 0, -1, 1> const, 0, Eigen::InnerStride<1> > const&, double) ()
    at /home/christian/Development/mpe_io_ws/devel/lib//libexotica_ompl_solver.so
#13 0x00007fffcae9bec9 in exotica::OMPLSolver<exotica::SamplingProblem>::Solve(Eigen::Matrix<double, -1, -1, 0, -1, -1>&) () at /home/christian/Development/mpe_io_ws/devel/lib//libexotica_ompl_solver.so
#14 0x00007ffff6161a99 in  () at /home/christian/Development/mpe_io_ws/devel/lib/python2.7/dist-packages/_pyexotica.so
#15 0x00007ffff6197d46 in  () at /home/christian/Development/mpe_io_ws/devel/lib/python2.7/dist-packages/_pyexotica.so
#16 0x0000555555651fe5 in PyEval_EvalFrameEx ()
#17 0x0000555555647d0a in PyEval_EvalCodeEx ()
#18 0x0000555555647629 in PyEval_EvalCode ()
#19 0x000055555567861f in  ()
#20 0x0000555555673322 in PyRun_FileExFlags ()
#21 0x000055555567267d in PyRun_SimpleFileExFlags ()
#22 0x00005555556211ab in Py_Main ()
#23 0x00007ffff7a05b97 in __libc_start_main (main=0x555555620b10 <main>, argc=2, argv=0x7fffffffca48, init=<optimised out>, fini=<optimised out>, rtld_fini=<optimised out>, stack_end=0x7fffffffca38)
    at ../csu/libc-start.c:310
#24 0x0000555555620a2a in _start ()

Edit: I imagine that collision checking with planes is not well supported since planes do not have a volume. However, even if FCL does not support planes, EXOTica should throw a warning instead of crashing. Is mesh to plane collision supported in FCL and MoveIt!?

VladimirIvan commented 5 years ago

However, even if FCL does not support planes, EXOTica should throw a warning instead of crashing.

Absolutely

MoveIt uses FCL so they have the same limitation.

wxmerkt commented 5 years ago

I'd like to test this with your minimal example from above. It should work with CollisionSceneFCLLatest (new FCL has some half-space fixes). I will report back once done.

wxmerkt commented 5 years ago

I did some more digging: the issue is related with the dispatch via the DynamicAABBTreeManager. Adding a plane and box by themselves and checking with isCollisionFree by themselves is fine:

import pyexotica as exo

ik = exo.Setup.loadSolver('{exotica_examples}/resources/configs/example_manipulate_ik.xml')
problem = ik.getProblem()
scene = problem.getScene()

test_scene = '''(ExampleScene)+
* Box
1
box
0.1 0.1 0.1
0 0 0
0 0 0.968912 -0.247404
1 0 0 1
* Plane
1
plane
0 0 1.0 0
0 0 -0.5
0 0 0 1
0 0 1 1
.
'''

scene.cleanScene()
scene.loadScene(test_scene)
print("Collision-free?", scene.isCollisionFree("Box", "Plane"))
print("isStateValid(False, 0.01)?", scene.isStateValid(False, 0.01))

While the parameter d has an influence on the AABB (cf. here), changing it to a small value (1e-6, 1e-2) did not help. I checked with MoveIt again and they do the same setup and similar dispatch as we do. Strangely enough, they have a special if-case for planes, but then treat it the same as other shapes in the end.