Files
bullet3/examples/pybullet/examples/configureDebugVisualizer.py
Erwin Coumans ed4515ae17 for the GraphicsServer, expose a sync transform interval: only synchronize the transform once the stepSimulation exceeds this time interval.
(for example, run the simulation at 1kHz but sync the graphics transforms to remove graphics server at 30Hz)
2019-06-19 09:45:29 -07:00

21 lines
419 B
Python

import pybullet as p
import math
import time
dt = 1./240.
p.connect(p.GUI)
p.loadURDF("r2d2.urdf",[0,0,1])
p.loadURDF("plane.urdf")
p.setGravity(0,0,-10)
radius=5
t = 0
p.configureDebugVisualizer(shadowMapWorldSize=5)
p.configureDebugVisualizer(shadowMapResolution=8192)
while (1):
t+=dt
p.configureDebugVisualizer(lightPosition=[radius*math.sin(t),radius*math.cos(t),3])
p.stepSimulation()
time.sleep(dt)