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:
@@ -1,11 +1,18 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
|
||||
#you can visualize the timings using Google Chrome, visit about://tracing
|
||||
#and load the json file
|
||||
p.connect(p.GUI)
|
||||
|
||||
t = time.time() + 0.1
|
||||
t = time.time() + 3.1
|
||||
|
||||
logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "haha")
|
||||
logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "chrome_about_tracing.json")
|
||||
while (time.time() < t):
|
||||
p.submitProfileTiming("pythontest")
|
||||
time.sleep(1./240.)
|
||||
p.submitProfileTiming("nested")
|
||||
time.sleep(1./1000.)
|
||||
p.submitProfileTiming()
|
||||
p.submitProfileTiming()
|
||||
|
||||
p.stopStateLogging(logId)
|
||||
|
||||
@@ -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;
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user