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)

This commit is contained in:
erwincoumans
2018-06-12 16:10:49 -07:00
parent 97c6937388
commit 459d07a302
2 changed files with 46 additions and 0 deletions

View File

@@ -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.)