set a smaller dt for deformable_ball.py for stability and typo fix

This commit is contained in:
Xuchen Han
2019-11-25 15:46:21 -08:00
parent abd7a556e1
commit 39df98465e
3 changed files with 4 additions and 5 deletions

View File

@@ -13,6 +13,7 @@ planeId = p.loadURDF("plane.urdf", [0,0,-2],planeOrn)
boxId = p.loadURDF("cube.urdf", [0,3,2],useMaximalCoordinates = True)
ballId = p.loadSoftBody("ball.vtk", basePosition = [0,0,-1], scale = 0.5, mass = 0.1, useNeoHookean = 1, NeoHookeanMu = 20, NeoHookeanLambda = 20, NeoHookeanDamping = 0.001, useSelfCollision = 1, frictionCoeff = .5)
p.setTimeStep(0.001)
p.setPhysicsEngineParameter(sparseSdfVoxelSize=0.25)
p.setRealTimeSimulation(1)