diff options
author | erwincoumans <erwin.coumans@gmail.com> | 2018-06-12 16:10:49 -0700 |
---|---|---|
committer | erwincoumans <erwin.coumans@gmail.com> | 2018-06-12 16:10:49 -0700 |
commit | 459d07a302cae23febd752b4b2b1d0b2f28143ca (patch) | |
tree | 0a2f5777a409069c36ac412e6f2502bca8c3983f | |
parent | 97c693738897f48e0876086b31cc1fc5c13ea41f (diff) | |
download | bullet3-459d07a302cae23febd752b4b2b1d0b2f28143ca.tar.gz |
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)
-rw-r--r-- | data/cube_concave.urdf | 32 | ||||
-rw-r--r-- | examples/pybullet/examples/satCollision.py | 14 |
2 files changed, 46 insertions, 0 deletions
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 @@ +<?xml version="0.0" ?> +<robot name="cube"> + <link name="baseLink"> + <contact> + <lateral_friction value="1.0"/> + <rolling_friction value="0.0"/> + <contact_cfm value="0.0"/> + <contact_erp value="1.0"/> + </contact> + <inertial> + <origin rpy="0 0 0" xyz="0 0 0"/> + <mass value="1.0"/> + <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/> + </inertial> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="cube.obj" scale="1 1 1"/> + </geometry> + <material name="white"> + <color rgba="1 1 1 1"/> + </material> + </visual> + <collision concave="yes"> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <mesh filename="cube.obj" scale="1 1 1"/> + </geometry> + </collision> + </link> +</robot> + 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 |