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

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