expose shadowMapResolution (texture resolution) and shadowMapWorldSize (size in meters in world space)
expose pybullet.ConfigureOpenGLVisualizerRequest(lightPosition=[x,y,z], shadowMapWorldSize=10.5, shadowMapResolution=16384) See examples/pybullet/examples/configureDebugVisualizer.py for an example. This reimplements https://github.com/bulletphysics/bullet3/pull/2295 but without creating a new command/status and explicitly referring to the debug visualizer (since the 'getCameraImage' also has a lightPosition)
This commit is contained in:
20
examples/pybullet/examples/configureDebugVisualizer.py
Normal file
20
examples/pybullet/examples/configureDebugVisualizer.py
Normal file
@@ -0,0 +1,20 @@
|
||||
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)
|
||||
Reference in New Issue
Block a user