Files
bullet3/examples/pybullet/examples/heightfield.py
Erwin Coumans 51fba6f78d export btHeightfieldTerrainShape to PyBullet. Note that tinyrenderer doesn't support rendering it (it would be too slow on CPU)
fix rare getKeyboardEvents threading issue
change texture color to default plane.urdf blue
2019-07-29 20:23:38 -07:00

94 lines
3.5 KiB
Python

import pybullet as p
import pybullet_data as pd
import time
p.connect(p.GUI)
p.setAdditionalSearchPath(pd.getDataPath())
textureId = -1
useDeepLocoCSV = False
if useDeepLocoCSV:
terrainShape = p.createCollisionShape(shapeType = p.GEOM_HEIGHTFIELD, meshScale=[.5,.5,2.5],fileName = "heightmaps/ground0.txt", heightfieldTextureScaling=128)#Image8x4.png")#wm_height_out.png")
terrain = p.createMultiBody(0, terrainShape)
p.resetBasePositionAndOrientation(terrain,[-8,0,-2], [0,0,0,1])
else:
terrainShape = p.createCollisionShape(shapeType = p.GEOM_HEIGHTFIELD, meshScale=[.1,.1,24],fileName = "heightmaps/wm_height_out.png")
textureId = p.loadTexture("heightmaps/gimp_overlay_out.png")
terrain = p.createMultiBody(0, terrainShape)
p.changeVisualShape(terrain, -1, textureUniqueId = textureId)
p.changeVisualShape(terrain, -1, rgbaColor=[1,1,1,1])
sphereRadius = 0.05
colSphereId = p.createCollisionShape(p.GEOM_SPHERE, radius=sphereRadius)
colBoxId = p.createCollisionShape(p.GEOM_BOX,
halfExtents=[sphereRadius, sphereRadius, sphereRadius])
mass = 1
visualShapeId = -1
link_Masses = [1]
linkCollisionShapeIndices = [colBoxId]
linkVisualShapeIndices = [-1]
linkPositions = [[0, 0, 0.11]]
linkOrientations = [[0, 0, 0, 1]]
linkInertialFramePositions = [[0, 0, 0]]
linkInertialFrameOrientations = [[0, 0, 0, 1]]
indices = [0]
jointTypes = [p.JOINT_REVOLUTE]
axis = [[0, 0, 1]]
for i in range(3):
for j in range(3):
for k in range(3):
basePosition = [
i * 5 * sphereRadius, j * 5 * sphereRadius, 1 + k * 5 * sphereRadius + 1
]
baseOrientation = [0, 0, 0, 1]
if (k & 2):
sphereUid = p.createMultiBody(mass, colSphereId, visualShapeId, basePosition,
baseOrientation)
else:
sphereUid = p.createMultiBody(mass,
colBoxId,
visualShapeId,
basePosition,
baseOrientation,
linkMasses=link_Masses,
linkCollisionShapeIndices=linkCollisionShapeIndices,
linkVisualShapeIndices=linkVisualShapeIndices,
linkPositions=linkPositions,
linkOrientations=linkOrientations,
linkInertialFramePositions=linkInertialFramePositions,
linkInertialFrameOrientations=linkInertialFrameOrientations,
linkParentIndices=indices,
linkJointTypes=jointTypes,
linkJointAxis=axis)
p.changeDynamics(sphereUid,
-1,
spinningFriction=0.001,
rollingFriction=0.001,
linearDamping=0.0)
for joint in range(p.getNumJoints(sphereUid)):
p.setJointMotorControl2(sphereUid, joint, p.VELOCITY_CONTROL, targetVelocity=1, force=10)
p.setGravity(0, 0, -10)
p.setRealTimeSimulation(1)
p.getNumJoints(sphereUid)
for i in range(p.getNumJoints(sphereUid)):
p.getJointInfo(sphereUid, i)
while (1):
keys = p.getKeyboardEvents()
print(keys)
#getCameraImage note: software/TinyRenderer doesn't render/support heightfields!
#p.getCameraImage(320,200, renderer=p.ER_BULLET_HARDWARE_OPENGL)
time.sleep(0.01)