pybullet: allow programmatic creation of heightfield. See https://github.com/erwincoumans/bullet3/tree/master/examples/pybullet/examples/heightfield.py
premake4: allow to build example browser without C++11, re-enable stable PD control plugin using --enable_stable_pd=True
This commit is contained in:
@@ -7,13 +7,39 @@ 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")
|
||||
useProgrammatic = 0
|
||||
useTerrainFromPNG = 1
|
||||
useDeepLocoCSV = 2
|
||||
|
||||
heightfieldSource = useProgrammatic
|
||||
import random
|
||||
random.seed(10)
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||
heightPerturbationRange = 0.05
|
||||
if heightfieldSource==useProgrammatic:
|
||||
numHeightfieldRows = 256
|
||||
numHeightfieldColumns = 256
|
||||
heightfieldData = [0]*numHeightfieldRows*numHeightfieldColumns
|
||||
for j in range (int(numHeightfieldColumns/2)):
|
||||
for i in range (int(numHeightfieldRows/2) ):
|
||||
height = random.uniform(0,heightPerturbationRange)
|
||||
heightfieldData[2*i+2*j*numHeightfieldRows]=height
|
||||
heightfieldData[2*i+1+2*j*numHeightfieldRows]=height
|
||||
heightfieldData[2*i+(2*j+1)*numHeightfieldRows]=height
|
||||
heightfieldData[2*i+1+(2*j+1)*numHeightfieldRows]=height
|
||||
|
||||
|
||||
terrainShape = p.createCollisionShape(shapeType = p.GEOM_HEIGHTFIELD, meshScale=[.05,.05,1], heightfieldTextureScaling=(numHeightfieldRows-1)/2, heightfieldData=heightfieldData, numHeightfieldRows=numHeightfieldRows, numHeightfieldColumns=numHeightfieldColumns, )
|
||||
terrain = p.createMultiBody(0, terrainShape)
|
||||
p.resetBasePositionAndOrientation(terrain,[-8,0,-2], [0,0,0,1])
|
||||
else:
|
||||
p.resetBasePositionAndOrientation(terrain,[0,0,0], [0,0,0,1])
|
||||
|
||||
if heightfieldSource==useDeepLocoCSV:
|
||||
terrainShape = p.createCollisionShape(shapeType = p.GEOM_HEIGHTFIELD, meshScale=[.5,.5,2.5],fileName = "heightmaps/ground0.txt", heightfieldTextureScaling=128)
|
||||
terrain = p.createMultiBody(0, terrainShape)
|
||||
p.resetBasePositionAndOrientation(terrain,[0,0,0], [0,0,0,1])
|
||||
|
||||
if heightfieldSource==useTerrainFromPNG:
|
||||
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)
|
||||
@@ -78,6 +104,7 @@ for i in range(3):
|
||||
for joint in range(p.getNumJoints(sphereUid)):
|
||||
p.setJointMotorControl2(sphereUid, joint, p.VELOCITY_CONTROL, targetVelocity=1, force=10)
|
||||
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||
p.setGravity(0, 0, -10)
|
||||
p.setRealTimeSimulation(1)
|
||||
|
||||
@@ -85,9 +112,10 @@ p.getNumJoints(sphereUid)
|
||||
for i in range(p.getNumJoints(sphereUid)):
|
||||
p.getJointInfo(sphereUid, i)
|
||||
|
||||
while (1):
|
||||
keys = p.getKeyboardEvents()
|
||||
print(keys)
|
||||
|
||||
while (p.isConnected()):
|
||||
#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)
|
||||
|
||||
Reference in New Issue
Block a user