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

@@ -49,6 +49,9 @@ struct CommonRenderInterface
virtual void setLightPosition(const float lightPos[3]) = 0;
virtual void setLightPosition(const double lightPos[3]) = 0;
virtual void setShadowMapResolution(int shadowMapResolution) = 0;
virtual void setShadowMapWorldSize(float worldSize) = 0;
virtual void setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]){};
virtual void setProjectiveTexture(bool useProjectiveTexture){};

View File

@@ -16,9 +16,8 @@ subject to the following restrictions:
///todo: make this configurable in the gui
bool useShadowMap = true; // true;//false;//true;
int shadowMapWidth = 4096;
int shadowMapHeight = 4096;
float shadowMapWorldSize = 10;
#include <stdio.h>
struct caster2
@@ -244,11 +243,22 @@ struct InternalDataRenderer : public GLInstanceRendererInternalData
b3ResizablePool<b3PublicGraphicsInstance> m_publicGraphicsInstances;
int m_shadowMapWidth;
int m_shadowMapHeight;
float m_shadowMapWorldSize;
bool m_updateShadowMap;
InternalDataRenderer() : m_activeCamera(&m_defaultCamera1),
m_shadowMap(0),
m_shadowTexture(0),
m_renderFrameBuffer(0)
m_renderFrameBuffer(0),
m_shadowMapWidth(4096),
m_shadowMapHeight(4096),
m_shadowMapWorldSize(10),
m_updateShadowMap(true)
{
m_lightPos = b3MakeVector3(-50, 30, 40);
m_lightSpecularIntensity.setValue(1, 1, 1);
@@ -1449,6 +1459,19 @@ void GLInstancingRenderer::setLightPosition(const float lightPos[3])
m_data->m_lightPos[2] = lightPos[2];
}
void GLInstancingRenderer::setShadowMapResolution(int shadowMapResolution)
{
m_data->m_shadowMapWidth = shadowMapResolution;
m_data->m_shadowMapHeight = shadowMapResolution;
m_data->m_updateShadowMap = true;
}
void GLInstancingRenderer::setShadowMapWorldSize(float worldSize)
{
m_data->m_shadowMapWorldSize = worldSize;
m_data->m_updateShadowMap = true;
}
void GLInstancingRenderer::setLightPosition(const double lightPos[3])
{
m_data->m_lightPos[0] = lightPos[0];
@@ -2071,6 +2094,13 @@ void GLInstancingRenderer::renderSceneInternal(int orgRenderMode)
glEnable(GL_CULL_FACE);
glCullFace(GL_FRONT);
if (m_data->m_shadowMap && m_data->m_updateShadowMap)
{
m_data->m_updateShadowMap = false;
glDeleteTextures(1, &m_data->m_shadowTexture);
delete m_data->m_shadowMap;
m_data->m_shadowMap = 0;
}
if (!m_data->m_shadowMap)
{
glActiveTexture(GL_TEXTURE0);
@@ -2088,27 +2118,27 @@ void GLInstancingRenderer::renderSceneInternal(int orgRenderMode)
int size;
glGetIntegerv(GL_MAX_TEXTURE_SIZE, &size);
if (size < shadowMapWidth)
if (size < m_data->m_shadowMapWidth)
{
shadowMapWidth = size;
m_data->m_shadowMapWidth = size;
}
if (size < shadowMapHeight)
if (size < m_data->m_shadowMapHeight)
{
shadowMapHeight = size;
m_data->m_shadowMapHeight = size;
}
GLuint err;
do
{
glTexImage2D(GL_TEXTURE_2D, 0, GL_DEPTH_COMPONENT16,
shadowMapWidth, shadowMapHeight,
m_data->m_shadowMapWidth, m_data->m_shadowMapHeight,
0, GL_DEPTH_COMPONENT, GL_FLOAT, 0);
err = glGetError();
if (err != GL_NO_ERROR)
{
shadowMapHeight >>= 1;
shadowMapWidth >>= 1;
m_data->m_shadowMapHeight >>= 1;
m_data->m_shadowMapWidth >>= 1;
}
} while (err != GL_NO_ERROR && shadowMapWidth > 0);
} while (err != GL_NO_ERROR && m_data->m_shadowMapWidth > 0);
#endif //OLD_SHADOWMAP_INIT
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR);
@@ -2124,10 +2154,10 @@ void GLInstancingRenderer::renderSceneInternal(int orgRenderMode)
glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_COMPARE_MODE, GL_COMPARE_REF_TO_TEXTURE);
m_data->m_shadowMap = new GLRenderToTexture();
m_data->m_shadowMap->init(shadowMapWidth, shadowMapHeight, m_data->m_shadowTexture, RENDERTEXTURE_DEPTH);
m_data->m_shadowMap->init(m_data->m_shadowMapWidth, m_data->m_shadowMapHeight, m_data->m_shadowTexture, RENDERTEXTURE_DEPTH);
}
m_data->m_shadowMap->enable();
glViewport(0, 0, shadowMapWidth, shadowMapHeight);
glViewport(0, 0, m_data->m_shadowMapWidth, m_data->m_shadowMapHeight);
//glClearColor(1,1,1,1);
glClear(GL_DEPTH_BUFFER_BIT);
//glClearColor(0.3,0.3,0.3,1);
@@ -2145,7 +2175,7 @@ void GLInstancingRenderer::renderSceneInternal(int orgRenderMode)
glCullFace(GL_BACK);
}
b3CreateOrtho(-shadowMapWorldSize, shadowMapWorldSize, -shadowMapWorldSize, shadowMapWorldSize, 1, 300, depthProjectionMatrix); //-14,14,-14,14,1,200, depthProjectionMatrix);
b3CreateOrtho(-m_data->m_shadowMapWorldSize, m_data->m_shadowMapWorldSize, -m_data->m_shadowMapWorldSize, m_data->m_shadowMapWorldSize, 1, 300, depthProjectionMatrix); //-14,14,-14,14,1,200, depthProjectionMatrix);
float depthViewMatrix[4][4];
b3Vector3 center = b3MakeVector3(0, 0, 0);
m_data->m_activeCamera->getCameraTargetPosition(center);

View File

@@ -120,6 +120,8 @@ public:
virtual void setLightPosition(const float lightPos[3]);
virtual void setLightPosition(const double lightPos[3]);
virtual void setShadowMapResolution(int shadowMapResolution);
virtual void setShadowMapWorldSize(float worldSize);
void setLightSpecularIntensity(const float lightSpecularIntensity[3]);
virtual void setProjectiveTextureMatrices(const float viewMatrix[16], const float projectionMatrix[16]);
virtual void setProjectiveTexture(bool useProjectiveTexture);

View File

@@ -26,7 +26,8 @@ public:
virtual void setLightPosition(const float lightPos[3]);
virtual void setLightPosition(const double lightPos[3]);
virtual void setShadowMapResolution(int shadowMapResolution) {}
virtual void setShadowMapWorldSize(float worldSize) {}
virtual void resize(int width, int height);
virtual void removeAllInstances();

View File

@@ -26,7 +26,7 @@ typedef unsigned long long int smUint64a_t;
#ifdef __APPLE__
#define GRAPHICS_SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE (512 * 1024)
#else
#define GRAPHICS_SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE (4 * 1024 * 1024)
#define GRAPHICS_SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE (4 * 1024 * 1024)
#endif
struct GraphicsCommand0

View File

@@ -5462,6 +5462,45 @@ B3_SHARED_API void b3ConfigureOpenGLVisualizerSetVisualizationFlags(b3SharedMemo
}
}
B3_SHARED_API void b3ConfigureOpenGLVisualizerSetLightPosition(b3SharedMemoryCommandHandle commandHandle, const float lightPosition[3])
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_CONFIGURE_OPENGL_VISUALIZER);
if (command->m_type == CMD_CONFIGURE_OPENGL_VISUALIZER)
{
command->m_updateFlags |= COV_SET_LIGHT_POSITION;
command->m_configureOpenGLVisualizerArguments.m_lightPosition[0] = lightPosition[0];
command->m_configureOpenGLVisualizerArguments.m_lightPosition[1] = lightPosition[1];
command->m_configureOpenGLVisualizerArguments.m_lightPosition[2] = lightPosition[2];
}
}
B3_SHARED_API void b3ConfigureOpenGLVisualizerSetShadowMapResolution(b3SharedMemoryCommandHandle commandHandle, int shadowMapResolution)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_CONFIGURE_OPENGL_VISUALIZER);
if (command->m_type == CMD_CONFIGURE_OPENGL_VISUALIZER)
{
command->m_updateFlags |= COV_SET_SHADOWMAP_RESOLUTION;
command->m_configureOpenGLVisualizerArguments.m_shadowMapResolution = shadowMapResolution;
}
}
B3_SHARED_API void b3ConfigureOpenGLVisualizerSetShadowMapWorldSize(b3SharedMemoryCommandHandle commandHandle, int shadowMapWorldSize)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_CONFIGURE_OPENGL_VISUALIZER);
if (command->m_type == CMD_CONFIGURE_OPENGL_VISUALIZER)
{
command->m_updateFlags |= COV_SET_SHADOWMAP_WORLD_SIZE;
command->m_configureOpenGLVisualizerArguments.m_shadowMapWorldSize = shadowMapWorldSize;
}
}
B3_SHARED_API void b3ConfigureOpenGLVisualizerSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, const float cameraTargetPosition[3])
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;

View File

@@ -207,6 +207,10 @@ extern "C"
B3_SHARED_API b3SharedMemoryCommandHandle b3InitConfigureOpenGLVisualizer(b3PhysicsClientHandle physClient);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitConfigureOpenGLVisualizer2(b3SharedMemoryCommandHandle commandHandle);
B3_SHARED_API void b3ConfigureOpenGLVisualizerSetVisualizationFlags(b3SharedMemoryCommandHandle commandHandle, int flag, int enabled);
B3_SHARED_API void b3ConfigureOpenGLVisualizerSetLightPosition(b3SharedMemoryCommandHandle commandHandle, const float lightPosition[3]);
B3_SHARED_API void b3ConfigureOpenGLVisualizerSetShadowMapResolution(b3SharedMemoryCommandHandle commandHandle, int shadowMapResolution);
B3_SHARED_API void b3ConfigureOpenGLVisualizerSetShadowMapWorldSize(b3SharedMemoryCommandHandle commandHandle, int shadowMapWorldSize);
B3_SHARED_API void b3ConfigureOpenGLVisualizerSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, const float cameraTargetPosition[/*3*/]);
B3_SHARED_API b3SharedMemoryCommandHandle b3InitRequestOpenGLVisualizerCameraCommand(b3PhysicsClientHandle physClient);

View File

@@ -9058,6 +9058,22 @@ bool PhysicsServerCommandProcessor::processConfigureOpenGLVisualizerCommand(cons
clientCmd.m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[1],
clientCmd.m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[2]);
}
if (m_data->m_guiHelper->getRenderInterface())
{
if (clientCmd.m_updateFlags & COV_SET_LIGHT_POSITION)
{
m_data->m_guiHelper->getRenderInterface()->setLightPosition(clientCmd.m_configureOpenGLVisualizerArguments.m_lightPosition);
}
if (clientCmd.m_updateFlags & COV_SET_SHADOWMAP_RESOLUTION)
{
m_data->m_guiHelper->getRenderInterface()->setShadowMapResolution(clientCmd.m_configureOpenGLVisualizerArguments.m_shadowMapResolution);
}
if (clientCmd.m_updateFlags & COV_SET_SHADOWMAP_WORLD_SIZE)
{
float worldSize = clientCmd.m_configureOpenGLVisualizerArguments.m_shadowMapWorldSize;
m_data->m_guiHelper->getRenderInterface()->setShadowMapWorldSize(worldSize);
}
}
return hasStatus;
}

View File

@@ -905,6 +905,9 @@ enum InternalOpenGLVisualizerUpdateFlags
{
COV_SET_CAMERA_VIEW_MATRIX = 1,
COV_SET_FLAGS = 2,
COV_SET_LIGHT_POSITION = 4,
COV_SET_SHADOWMAP_RESOLUTION = 8,
COV_SET_SHADOWMAP_WORLD_SIZE = 16,
};
struct ConfigureOpenGLVisualizerRequest
@@ -913,7 +916,9 @@ struct ConfigureOpenGLVisualizerRequest
double m_cameraPitch;
double m_cameraYaw;
double m_cameraTargetPosition[3];
double m_lightPosition[3];
int m_shadowMapResolution;
int m_shadowMapWorldSize;
int m_setFlag;
int m_setEnabled;
};

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