for the GraphicsServer, expose a sync transform interval: only synchronize the transform once the stepSimulation exceeds this time interval.

(for example, run the simulation at 1kHz but sync the graphics transforms to remove graphics server at 30Hz)
This commit is contained in:
Erwin Coumans
2019-06-19 09:45:29 -07:00
parent c3b7f39aaf
commit ed4515ae17
6 changed files with 120 additions and 82 deletions

View File

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