Files
bullet3/examples/pybullet/examples/internalEdge.py
erwincoumans ddf304ca78 PyBullet: expose internal edge utility, to adjust edge normals to prevent object penetrating along triangle edges of concave triangle meshes
(due to local convex-triangle collisions causing opposite contact normals, use the pre-computed edge normal)
PyBullet: expose experimental continuous collision detection for maximal coordinate rigid bodies, to prevent tunneling.
2018-02-16 19:44:33 -08:00

42 lines
995 B
Python

import pybullet as p
import time
p.connect(p.GUI)
if (1):
box_collision_shape_id = p.createCollisionShape(
shapeType=p.GEOM_BOX,
halfExtents=[0.01,0.01,0.055])
box_mass=0.1
box_visual_shape_id = -1
box_position=[0,0.1,1]
box_orientation=[0,0,0,1]
p.createMultiBody(
box_mass, box_collision_shape_id, box_visual_shape_id,
box_position, box_orientation, useMaximalCoordinates=True)
terrain_mass=0
terrain_visual_shape_id=-1
terrain_position=[0,0,0]
terrain_orientation=[0,0,0,1]
terrain_collision_shape_id = p.createCollisionShape(
shapeType=p.GEOM_MESH,
fileName="terrain.obj",
flags=p.GEOM_FORCE_CONCAVE_TRIMESH|p.GEOM_CONCAVE_INTERNAL_EDGE,
meshScale=[0.5, 0.5, 0.5])
p.createMultiBody(
terrain_mass, terrain_collision_shape_id, terrain_visual_shape_id,
terrain_position, terrain_orientation)
p.setGravity(0,0,-10)
pts = p.getContactPoints()
print("num points=",len(pts))
print(pts)
while (p.isConnected()):
time.sleep(1./240.)
p.stepSimulation()