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:
Erwin Coumans
2019-06-19 09:01:16 -07:00
parent bc9c477edb
commit c3b7f39aaf
11 changed files with 166 additions and 24 deletions

View 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)

View File

@@ -5869,15 +5869,17 @@ static PyObject* pybullet_getDebugVisualizerCamera(PyObject* self, PyObject* arg
static PyObject* pybullet_configureDebugVisualizer(PyObject* self, PyObject* args, PyObject* keywds)
{
int flag = 1;
int flag = -1;
int enable = -1;
int shadowMapResolution = -1;
int shadowMapWorldSize = -1;
int physicsClientId = 0;
PyObject* pyLightPosition = 0;
b3PhysicsClientHandle sm = 0;
static char* kwlist[] = {"flag", "enable", "physicsClientId", NULL};
static char* kwlist[] = {"flag", "enable", "lightPosition", "shadowMapResolution", "shadowMapWorldSize", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|i", kwlist,
&flag, &enable, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|iiOiii", kwlist,
&flag, &enable, &pyLightPosition, &shadowMapResolution, &shadowMapWorldSize, &physicsClientId))
return NULL;
sm = getPhysicsClient(physicsClientId);
@@ -5889,7 +5891,27 @@ static PyObject* pybullet_configureDebugVisualizer(PyObject* self, PyObject* arg
{
b3SharedMemoryCommandHandle commandHandle = b3InitConfigureOpenGLVisualizer(sm);
b3ConfigureOpenGLVisualizerSetVisualizationFlags(commandHandle, flag, enable);
if (flag >= 0)
{
b3ConfigureOpenGLVisualizerSetVisualizationFlags(commandHandle, flag, enable);
}
if (pyLightPosition)
{
float lightPosition[3];
if (pybullet_internalSetVector(pyLightPosition, lightPosition))
{
b3ConfigureOpenGLVisualizerSetLightPosition(commandHandle, lightPosition);
}
}
if (shadowMapResolution > 0)
{
b3ConfigureOpenGLVisualizerSetShadowMapResolution(commandHandle, shadowMapResolution);
}
if (shadowMapWorldSize > 0)
{
b3ConfigureOpenGLVisualizerSetShadowMapWorldSize(commandHandle, shadowMapWorldSize);
}
b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
}
Py_INCREF(Py_None);