fix saveRestoreState.py example
This commit is contained in:
@@ -16,11 +16,15 @@ gravYid = p.addUserDebugParameter("gravityY",-10,10,0)
|
||||
gravZid = p.addUserDebugParameter("gravityZ",-10,10,-10)
|
||||
p.setPhysicsEngineParameter(numSolverIterations=10)
|
||||
p.setPhysicsEngineParameter(contactBreakingThreshold=0.001)
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||
for i in range (10):
|
||||
for j in range (10):
|
||||
for k in range (10):
|
||||
ob = p.loadURDF("sphere_1cm.urdf",[0.02*i,0.02*j,0.2+0.02*k],useMaximalCoordinates=True)
|
||||
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
|
||||
p.setGravity(0,0,-10)
|
||||
|
||||
p.setRealTimeSimulation(1)
|
||||
while True:
|
||||
gravX = p.readUserDebugParameter(gravXid)
|
||||
|
||||
@@ -12,6 +12,7 @@ logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "saveRestoreTimings
|
||||
|
||||
def setupWorld():
|
||||
p.resetSimulation()
|
||||
p.setPhysicsEngineParameter(deterministicOverlappingPairs=1)
|
||||
p.loadURDF("planeMesh.urdf")
|
||||
kukaId = p.loadURDF("kuka_iiwa/model_free_base.urdf",[0,0,10])
|
||||
for i in range (p.getNumJoints(kukaId)):
|
||||
|
||||
Reference in New Issue
Block a user