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:
@@ -5276,8 +5276,8 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3ProfileTimingCommandInit(b3PhysicsCl
|
|||||||
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
|
struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand();
|
||||||
b3Assert(command);
|
b3Assert(command);
|
||||||
|
|
||||||
int len = strlen(name);
|
int len = name ? strlen(name) : 0;
|
||||||
if (len >= 0 && len < (MAX_FILENAME_LENGTH + 1))
|
if (len > 0 && len < (MAX_FILENAME_LENGTH + 1))
|
||||||
{
|
{
|
||||||
command->m_type = CMD_PROFILE_TIMING;
|
command->m_type = CMD_PROFILE_TIMING;
|
||||||
strcpy(command->m_profile.m_name, name);
|
strcpy(command->m_profile.m_name, name);
|
||||||
@@ -5290,6 +5290,7 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3ProfileTimingCommandInit(b3PhysicsCl
|
|||||||
strcpy(command->m_profile.m_name, invalid);
|
strcpy(command->m_profile.m_name, invalid);
|
||||||
command->m_profile.m_name[len] = 0;
|
command->m_profile.m_name[len] = 0;
|
||||||
}
|
}
|
||||||
|
command->m_profile.m_type = -1;
|
||||||
command->m_profile.m_durationInMicroSeconds = 0;
|
command->m_profile.m_durationInMicroSeconds = 0;
|
||||||
return (b3SharedMemoryCommandHandle)command;
|
return (b3SharedMemoryCommandHandle)command;
|
||||||
}
|
}
|
||||||
@@ -5319,6 +5320,18 @@ B3_SHARED_API void b3SetProfileTimingDuractionInMicroSeconds(b3SharedMemoryComma
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
B3_SHARED_API void b3SetProfileTimingType(b3SharedMemoryCommandHandle commandHandle, int type)
|
||||||
|
{
|
||||||
|
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*)commandHandle;
|
||||||
|
b3Assert(command);
|
||||||
|
b3Assert(command->m_type == CMD_PROFILE_TIMING);
|
||||||
|
if (command->m_type == CMD_PROFILE_TIMING)
|
||||||
|
{
|
||||||
|
command->m_profile.m_type = type;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
B3_SHARED_API b3SharedMemoryCommandHandle b3StateLoggingCommandInit(b3PhysicsClientHandle physClient)
|
B3_SHARED_API b3SharedMemoryCommandHandle b3StateLoggingCommandInit(b3PhysicsClientHandle physClient)
|
||||||
{
|
{
|
||||||
PhysicsClient* cl = (PhysicsClient*)physClient;
|
PhysicsClient* cl = (PhysicsClient*)physClient;
|
||||||
|
|||||||
@@ -664,6 +664,7 @@ extern "C"
|
|||||||
|
|
||||||
B3_SHARED_API b3SharedMemoryCommandHandle b3ProfileTimingCommandInit(b3PhysicsClientHandle physClient, const char* name);
|
B3_SHARED_API b3SharedMemoryCommandHandle b3ProfileTimingCommandInit(b3PhysicsClientHandle physClient, const char* name);
|
||||||
B3_SHARED_API void b3SetProfileTimingDuractionInMicroSeconds(b3SharedMemoryCommandHandle commandHandle, int duration);
|
B3_SHARED_API void b3SetProfileTimingDuractionInMicroSeconds(b3SharedMemoryCommandHandle commandHandle, int duration);
|
||||||
|
B3_SHARED_API void b3SetProfileTimingType(b3SharedMemoryCommandHandle commandHandle, int type);
|
||||||
|
|
||||||
B3_SHARED_API void b3PushProfileTiming(b3PhysicsClientHandle physClient, const char* timingName);
|
B3_SHARED_API void b3PushProfileTiming(b3PhysicsClientHandle physClient, const char* timingName);
|
||||||
B3_SHARED_API void b3PopProfileTiming(b3PhysicsClientHandle physClient);
|
B3_SHARED_API void b3PopProfileTiming(b3PhysicsClientHandle physClient);
|
||||||
|
|||||||
@@ -8037,19 +8037,21 @@ bool PhysicsServerCommandProcessor::processProfileTimingCommand(const struct Sha
|
|||||||
{
|
{
|
||||||
bool hasStatus = true;
|
bool hasStatus = true;
|
||||||
|
|
||||||
B3_PROFILE("custom"); //clientCmd.m_profile.m_name);
|
|
||||||
{
|
{
|
||||||
B3_PROFILE("event"); //clientCmd.m_profile.m_name);
|
if (clientCmd.m_profile.m_type == 0)
|
||||||
|
{
|
||||||
|
|
||||||
char** eventNamePtr = m_data->m_profileEvents[clientCmd.m_profile.m_name];
|
char** eventNamePtr = m_data->m_profileEvents[clientCmd.m_profile.m_name];
|
||||||
char* eventName = 0;
|
char* eventName = 0;
|
||||||
if (eventNamePtr)
|
if (eventNamePtr)
|
||||||
{
|
{
|
||||||
B3_PROFILE("reuse");
|
|
||||||
eventName = *eventNamePtr;
|
eventName = *eventNamePtr;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
B3_PROFILE("alloc");
|
|
||||||
int len = strlen(clientCmd.m_profile.m_name);
|
int len = strlen(clientCmd.m_profile.m_name);
|
||||||
eventName = new char[len + 1];
|
eventName = new char[len + 1];
|
||||||
strcpy(eventName, clientCmd.m_profile.m_name);
|
strcpy(eventName, clientCmd.m_profile.m_name);
|
||||||
@@ -8057,24 +8059,13 @@ bool PhysicsServerCommandProcessor::processProfileTimingCommand(const struct Sha
|
|||||||
m_data->m_profileEvents.insert(eventName, eventName);
|
m_data->m_profileEvents.insert(eventName, eventName);
|
||||||
}
|
}
|
||||||
|
|
||||||
{
|
b3EnterProfileZone(eventName);
|
||||||
{
|
|
||||||
B3_PROFILE("with"); //clientCmd.m_profile.m_name);
|
|
||||||
{
|
|
||||||
B3_PROFILE("some"); //clientCmd.m_profile.m_name);
|
|
||||||
{
|
|
||||||
B3_PROFILE("deep"); //clientCmd.m_profile.m_name);
|
|
||||||
{
|
|
||||||
B3_PROFILE("level"); //clientCmd.m_profile.m_name);
|
|
||||||
{
|
|
||||||
B3_PROFILE(eventName);
|
|
||||||
b3Clock::usleep(clientCmd.m_profile.m_durationInMicroSeconds);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
if (clientCmd.m_profile.m_type == 1)
|
||||||
|
{
|
||||||
|
b3LeaveProfileZone();
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
serverStatusOut.m_type = CMD_CLIENT_COMMAND_COMPLETED;
|
serverStatusOut.m_type = CMD_CLIENT_COMMAND_COMPLETED;
|
||||||
|
|||||||
@@ -627,6 +627,7 @@ struct b3Profile
|
|||||||
{
|
{
|
||||||
char m_name[MAX_FILENAME_LENGTH];
|
char m_name[MAX_FILENAME_LENGTH];
|
||||||
int m_durationInMicroSeconds;
|
int m_durationInMicroSeconds;
|
||||||
|
int m_type;
|
||||||
};
|
};
|
||||||
|
|
||||||
struct SdfLoadedArgs
|
struct SdfLoadedArgs
|
||||||
|
|||||||
@@ -1,11 +1,18 @@
|
|||||||
import pybullet as p
|
import pybullet as p
|
||||||
import time
|
import time
|
||||||
|
#you can visualize the timings using Google Chrome, visit about://tracing
|
||||||
|
#and load the json file
|
||||||
p.connect(p.GUI)
|
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):
|
while (time.time() < t):
|
||||||
p.submitProfileTiming("pythontest")
|
p.submitProfileTiming("pythontest")
|
||||||
|
time.sleep(1./240.)
|
||||||
|
p.submitProfileTiming("nested")
|
||||||
|
time.sleep(1./1000.)
|
||||||
|
p.submitProfileTiming()
|
||||||
|
p.submitProfileTiming()
|
||||||
|
|
||||||
p.stopStateLogging(logId)
|
p.stopStateLogging(logId)
|
||||||
|
|||||||
@@ -6058,14 +6058,12 @@ static PyObject* pybullet_submitProfileTiming(PyObject* self, PyObject* args, Py
|
|||||||
// b3SharedMemoryStatusHandle statusHandle;
|
// b3SharedMemoryStatusHandle statusHandle;
|
||||||
// int statusType;
|
// int statusType;
|
||||||
char* eventName = 0;
|
char* eventName = 0;
|
||||||
int duractionInMicroSeconds = -1;
|
|
||||||
|
|
||||||
b3PhysicsClientHandle sm = 0;
|
b3PhysicsClientHandle sm = 0;
|
||||||
static char* kwlist[] = {"eventName ", "duraction", "physicsClientId", NULL};
|
static char* kwlist[] = {"eventName ", "physicsClientId", NULL};
|
||||||
int physicsClientId = 0;
|
int physicsClientId = 0;
|
||||||
|
|
||||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|ii", kwlist,
|
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|si", kwlist,
|
||||||
&eventName, &duractionInMicroSeconds, &physicsClientId))
|
&eventName, &physicsClientId))
|
||||||
return NULL;
|
return NULL;
|
||||||
|
|
||||||
sm = getPhysicsClient(physicsClientId);
|
sm = getPhysicsClient(physicsClientId);
|
||||||
@@ -6074,16 +6072,18 @@ static PyObject* pybullet_submitProfileTiming(PyObject* self, PyObject* args, Py
|
|||||||
PyErr_SetString(SpamError, "Not connected to physics server.");
|
PyErr_SetString(SpamError, "Not connected to physics server.");
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
if (eventName)
|
|
||||||
{
|
|
||||||
b3SharedMemoryCommandHandle commandHandle;
|
b3SharedMemoryCommandHandle commandHandle;
|
||||||
commandHandle = b3ProfileTimingCommandInit(sm, eventName);
|
commandHandle = b3ProfileTimingCommandInit(sm, eventName);
|
||||||
if (duractionInMicroSeconds >= 0)
|
|
||||||
|
if (eventName)
|
||||||
{
|
{
|
||||||
b3SetProfileTimingDuractionInMicroSeconds(commandHandle, duractionInMicroSeconds);
|
b3SetProfileTimingType(commandHandle, 0);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
b3SetProfileTimingType(commandHandle, 1);
|
||||||
}
|
}
|
||||||
b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
|
b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
|
||||||
}
|
|
||||||
Py_INCREF(Py_None);
|
Py_INCREF(Py_None);
|
||||||
return Py_None;
|
return Py_None;
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user