This commit is contained in:
Erwin Coumans
2019-06-19 12:08:52 -07:00
6 changed files with 120 additions and 82 deletions

View File

@@ -5501,6 +5501,19 @@ B3_SHARED_API void b3ConfigureOpenGLVisualizerSetShadowMapWorldSize(b3SharedMemo
} }
B3_SHARED_API void b3ConfigureOpenGLVisualizerSetRemoteSyncTransformInterval(b3SharedMemoryCommandHandle commandHandle, double remoteSyncTransformInterval)
{
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_REMOTE_SYNC_TRANSFORM_INTERVAL;
command->m_configureOpenGLVisualizerArguments.m_remoteSyncTransformInterval = remoteSyncTransformInterval;
}
}
B3_SHARED_API void b3ConfigureOpenGLVisualizerSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, const float cameraTargetPosition[3]) B3_SHARED_API void b3ConfigureOpenGLVisualizerSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, const float cameraTargetPosition[3])
{ {
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle; struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;

View File

@@ -210,6 +210,7 @@ extern "C"
B3_SHARED_API void b3ConfigureOpenGLVisualizerSetLightPosition(b3SharedMemoryCommandHandle commandHandle, const float lightPosition[3]); B3_SHARED_API void b3ConfigureOpenGLVisualizerSetLightPosition(b3SharedMemoryCommandHandle commandHandle, const float lightPosition[3]);
B3_SHARED_API void b3ConfigureOpenGLVisualizerSetShadowMapResolution(b3SharedMemoryCommandHandle commandHandle, int shadowMapResolution); B3_SHARED_API void b3ConfigureOpenGLVisualizerSetShadowMapResolution(b3SharedMemoryCommandHandle commandHandle, int shadowMapResolution);
B3_SHARED_API void b3ConfigureOpenGLVisualizerSetShadowMapWorldSize(b3SharedMemoryCommandHandle commandHandle, int shadowMapWorldSize); B3_SHARED_API void b3ConfigureOpenGLVisualizerSetShadowMapWorldSize(b3SharedMemoryCommandHandle commandHandle, int shadowMapWorldSize);
B3_SHARED_API void b3ConfigureOpenGLVisualizerSetRemoteSyncTransformInterval(b3SharedMemoryCommandHandle commandHandle, double remoteSyncTransformInterval);
B3_SHARED_API void b3ConfigureOpenGLVisualizerSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, const float cameraTargetPosition[/*3*/]); B3_SHARED_API void b3ConfigureOpenGLVisualizerSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, float cameraDistance, float cameraPitch, float cameraYaw, const float cameraTargetPosition[/*3*/]);

View File

@@ -1672,6 +1672,9 @@ struct PhysicsServerCommandProcessorInternalData
b3ThreadPool* m_threadPool; b3ThreadPool* m_threadPool;
btScalar m_defaultCollisionMargin; btScalar m_defaultCollisionMargin;
double m_remoteSyncTransformTime;
double m_remoteSyncTransformInterval;
PhysicsServerCommandProcessorInternalData(PhysicsCommandProcessorInterface* proc) PhysicsServerCommandProcessorInternalData(PhysicsCommandProcessorInterface* proc)
: m_pluginManager(proc), : m_pluginManager(proc),
m_useRealTimeSimulation(false), m_useRealTimeSimulation(false),
@@ -1705,7 +1708,9 @@ struct PhysicsServerCommandProcessorInternalData
m_collisionFilterPlugin(-1), m_collisionFilterPlugin(-1),
m_grpcPlugin(-1), m_grpcPlugin(-1),
m_threadPool(0), m_threadPool(0),
m_defaultCollisionMargin(0.001) m_defaultCollisionMargin(0.001),
m_remoteSyncTransformTime(1. / 30.),
m_remoteSyncTransformInterval(1. / 30.)
{ {
{ {
//register static plugins: //register static plugins:
@@ -1769,8 +1774,6 @@ struct PhysicsServerCommandProcessorInternalData
} }
#endif #endif
m_vrControllerEvents.init(); m_vrControllerEvents.init();
m_bodyHandles.exitHandles(); m_bodyHandles.exitHandles();
@@ -1868,7 +1871,6 @@ struct PhysicsServerCommandProcessorInternalData
int dof = 7; int dof = 7;
int veldof = 7; int veldof = 7;
for (int l = 0; l < multiBody->getNumLinks(); l++) for (int l = 0; l < multiBody->getNumLinks(); l++)
{ {
switch (multiBody->getLink(l).m_jointType) switch (multiBody->getLink(l).m_jointType)
@@ -7763,7 +7765,13 @@ bool PhysicsServerCommandProcessor::processForwardDynamicsCommand(const struct S
} }
serverCmd.m_type = CMD_STEP_FORWARD_SIMULATION_COMPLETED; serverCmd.m_type = CMD_STEP_FORWARD_SIMULATION_COMPLETED;
m_data->m_remoteSyncTransformTime += deltaTimeScaled;
if (m_data->m_remoteSyncTransformTime >= m_data->m_remoteSyncTransformInterval)
{
m_data->m_remoteSyncTransformTime = 0;
syncPhysicsToGraphics2(); syncPhysicsToGraphics2();
}
return hasStatus; return hasStatus;
} }
@@ -9074,6 +9082,13 @@ bool PhysicsServerCommandProcessor::processConfigureOpenGLVisualizerCommand(cons
m_data->m_guiHelper->getRenderInterface()->setShadowMapWorldSize(worldSize); m_data->m_guiHelper->getRenderInterface()->setShadowMapWorldSize(worldSize);
} }
} }
if (clientCmd.m_updateFlags & COV_SET_REMOTE_SYNC_TRANSFORM_INTERVAL)
{
m_data->m_remoteSyncTransformInterval = clientCmd.m_configureOpenGLVisualizerArguments.m_remoteSyncTransformInterval;
}
return hasStatus; return hasStatus;
} }
@@ -12047,6 +12062,7 @@ void PhysicsServerCommandProcessor::addTransformChangedNotifications()
void PhysicsServerCommandProcessor::resetSimulation() void PhysicsServerCommandProcessor::resetSimulation()
{ {
//clean up all data //clean up all data
m_data->m_remoteSyncTransformTime = m_data->m_remoteSyncTransformInterval;
m_data->m_simulationTimestamp = 0; m_data->m_simulationTimestamp = 0;
m_data->m_cachedVUrdfisualShapes.clear(); m_data->m_cachedVUrdfisualShapes.clear();

View File

@@ -908,6 +908,7 @@ enum InternalOpenGLVisualizerUpdateFlags
COV_SET_LIGHT_POSITION = 4, COV_SET_LIGHT_POSITION = 4,
COV_SET_SHADOWMAP_RESOLUTION = 8, COV_SET_SHADOWMAP_RESOLUTION = 8,
COV_SET_SHADOWMAP_WORLD_SIZE = 16, COV_SET_SHADOWMAP_WORLD_SIZE = 16,
COV_SET_REMOTE_SYNC_TRANSFORM_INTERVAL = 32,
}; };
struct ConfigureOpenGLVisualizerRequest struct ConfigureOpenGLVisualizerRequest
@@ -919,6 +920,7 @@ struct ConfigureOpenGLVisualizerRequest
double m_lightPosition[3]; double m_lightPosition[3];
int m_shadowMapResolution; int m_shadowMapResolution;
int m_shadowMapWorldSize; int m_shadowMapWorldSize;
double m_remoteSyncTransformInterval;
int m_setFlag; int m_setFlag;
int m_setEnabled; int m_setEnabled;
}; };

View File

@@ -12,6 +12,7 @@ radius=5
t = 0 t = 0
p.configureDebugVisualizer(shadowMapWorldSize=5) p.configureDebugVisualizer(shadowMapWorldSize=5)
p.configureDebugVisualizer(shadowMapResolution=8192) p.configureDebugVisualizer(shadowMapResolution=8192)
while (1): while (1):
t+=dt t+=dt
p.configureDebugVisualizer(lightPosition=[radius*math.sin(t),radius*math.cos(t),3]) p.configureDebugVisualizer(lightPosition=[radius*math.sin(t),radius*math.cos(t),3])

View File

@@ -5874,12 +5874,13 @@ static PyObject* pybullet_configureDebugVisualizer(PyObject* self, PyObject* arg
int shadowMapResolution = -1; int shadowMapResolution = -1;
int shadowMapWorldSize = -1; int shadowMapWorldSize = -1;
int physicsClientId = 0; int physicsClientId = 0;
double remoteSyncTransformInterval = -1;
PyObject* pyLightPosition = 0; PyObject* pyLightPosition = 0;
b3PhysicsClientHandle sm = 0; b3PhysicsClientHandle sm = 0;
static char* kwlist[] = {"flag", "enable", "lightPosition", "shadowMapResolution", "shadowMapWorldSize", "physicsClientId", NULL}; static char* kwlist[] = {"flag", "enable", "lightPosition", "shadowMapResolution", "shadowMapWorldSize", "remoteSyncTransformInterval", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|iiOiii", kwlist, if (!PyArg_ParseTupleAndKeywords(args, keywds, "|iiOiidi", kwlist,
&flag, &enable, &pyLightPosition, &shadowMapResolution, &shadowMapWorldSize, &physicsClientId)) &flag, &enable, &pyLightPosition, &shadowMapResolution, &shadowMapWorldSize, &remoteSyncTransformInterval, &physicsClientId))
return NULL; return NULL;
sm = getPhysicsClient(physicsClientId); sm = getPhysicsClient(physicsClientId);
@@ -5911,6 +5912,10 @@ static PyObject* pybullet_configureDebugVisualizer(PyObject* self, PyObject* arg
{ {
b3ConfigureOpenGLVisualizerSetShadowMapWorldSize(commandHandle, shadowMapWorldSize); b3ConfigureOpenGLVisualizerSetShadowMapWorldSize(commandHandle, shadowMapWorldSize);
} }
if (remoteSyncTransformInterval >= 0)
{
b3ConfigureOpenGLVisualizerSetRemoteSyncTransformInterval(commandHandle, remoteSyncTransformInterval);
}
b3SubmitClientCommandAndWaitStatus(sm, commandHandle); b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
} }