summaryrefslogtreecommitdiff
path: root/examples/pybullet/examples/switchConstraintSolver.py
blob: 1c44391f7131c3bfff778a039706cd9754d9e372 (plain)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
import pybullet as p
import time

p.connect(p.GUI)
#p.setPhysicsEngineParameter(constraintSolverType=p.CONSTRAINT_SOLVER_LCP_PGS, globalCFM = 0.0001)
p.setPhysicsEngineParameter(constraintSolverType=p.CONSTRAINT_SOLVER_LCP_DANTZIG,
                            globalCFM=0.000001)
#p.setPhysicsEngineParameter(constraintSolverType=p.CONSTRAINT_SOLVER_LCP_PGS, globalCFM = 0.0001)

p.loadURDF("plane.urdf")
radius = 0.025
distance = 1.86
yaw = 135
pitch = -11
targetPos = [0, 0, 0]

p.setPhysicsEngineParameter(solverResidualThreshold=0.001, numSolverIterations=200)
p.resetDebugVisualizerCamera(distance, yaw, pitch, targetPos)
objectId = -1

for i in range(10):
  objectId = p.loadURDF("cube_small.urdf", [1, 1, radius + i * 2 * radius])

p.changeDynamics(objectId, -1, 100)

timeStep = 1. / 240.
p.setGravity(0, 0, -10)
while (p.isConnected()):
  p.stepSimulation()
  time.sleep(timeStep)