preliminary work towards saveState/restoreState and saveRestoreState.py example (not implemented yet)

allow multiple options in connect, for example: p.connect(p.GUI, options="--width=640, --height=480")
This commit is contained in:
Erwin Coumans
2017-12-28 10:05:51 -08:00
parent 799d030874
commit 97547eda0d
15 changed files with 552 additions and 143 deletions

View File

@@ -0,0 +1,29 @@
import pybullet as p
import math, time
p.connect(p.GUI, options="--width=1024 --height=768")
p.loadURDF("plane.urdf")
for i in range (10):
cube = p.loadURDF("cube_small.urdf",0,i*0.01,i*0.5)
p.setGravity(0,0,-10)
for i in range (500):
p.stepSimulation()
for i in range (10):
print("pos[",i,"]=",p.getBasePositionAndOrientation(i))
#saveState = 0
#if saveState:
# for i in range (500):
# p.stepSimulation()
# p.saveBullet("state.bullet")
#else:
# p.restoreState(fileName="state.bullet")
while (p.getConnectionInfo()["isConnected"]):
time.sleep(1)