improved for inserting profile timings from Python, to analyzer performance of pybullet programs.

See examples/pybullet/examples/profileTiming.py for an example. Note that python and c++ is properly interleaved.
Open a timings with a name, close the timing without a name. Note that timings can be recursive, added/popped as a stack.
This commit is contained in:
Erwin Coumans
2019-08-01 19:12:16 -07:00
parent 397767cb60
commit 7263439c4b
6 changed files with 63 additions and 50 deletions

View File

@@ -6058,14 +6058,12 @@ static PyObject* pybullet_submitProfileTiming(PyObject* self, PyObject* args, Py
// b3SharedMemoryStatusHandle statusHandle;
// int statusType;
char* eventName = 0;
int duractionInMicroSeconds = -1;
b3PhysicsClientHandle sm = 0;
static char* kwlist[] = {"eventName ", "duraction", "physicsClientId", NULL};
static char* kwlist[] = {"eventName ", "physicsClientId", NULL};
int physicsClientId = 0;
if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|ii", kwlist,
&eventName, &duractionInMicroSeconds, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|si", kwlist,
&eventName, &physicsClientId))
return NULL;
sm = getPhysicsClient(physicsClientId);
@@ -6074,16 +6072,18 @@ static PyObject* pybullet_submitProfileTiming(PyObject* self, PyObject* args, Py
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
b3SharedMemoryCommandHandle commandHandle;
commandHandle = b3ProfileTimingCommandInit(sm, eventName);
if (eventName)
{
b3SharedMemoryCommandHandle commandHandle;
commandHandle = b3ProfileTimingCommandInit(sm, eventName);
if (duractionInMicroSeconds >= 0)
{
b3SetProfileTimingDuractionInMicroSeconds(commandHandle, duractionInMicroSeconds);
}
b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
b3SetProfileTimingType(commandHandle, 0);
}
else
{
b3SetProfileTimingType(commandHandle, 1);
}
b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
Py_INCREF(Py_None);
return Py_None;
}