From 459d07a302cae23febd752b4b2b1d0b2f28143ca Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Tue, 12 Jun 2018 16:10:49 -0700 Subject: [PATCH] add example for enableSAT, using separating axis test (instead of GJK) for contact between polyhedral convex hull shapes (and convex hull vs triangle in a concave triangle mesh) --- data/cube_concave.urdf | 32 ++++++++++++++++++++++ examples/pybullet/examples/satCollision.py | 14 ++++++++++ 2 files changed, 46 insertions(+) create mode 100644 data/cube_concave.urdf create mode 100644 examples/pybullet/examples/satCollision.py diff --git a/data/cube_concave.urdf b/data/cube_concave.urdf new file mode 100644 index 000000000..0124c5ab1 --- /dev/null +++ b/data/cube_concave.urdf @@ -0,0 +1,32 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/pybullet/examples/satCollision.py b/examples/pybullet/examples/satCollision.py new file mode 100644 index 000000000..84111bf6c --- /dev/null +++ b/examples/pybullet/examples/satCollision.py @@ -0,0 +1,14 @@ +import pybullet as p +import time + +p.connect(p.GUI) +p.setGravity(0,0,-10) +p.setPhysicsEngineParameter(enableSAT=1) +p.loadURDF("cube_concave.urdf",[0,0,-25], globalScaling=50, useFixedBase=True) +p.loadURDF("cube.urdf",[0,0,1], globalScaling=1) +p.loadURDF("duck_vhacd.urdf",[1,0,1], globalScaling=1) + +while (p.isConnected()): + p.stepSimulation() + time.sleep(1./240.) + \ No newline at end of file