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

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