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();
|
||||
b3Assert(command);
|
||||
|
||||
int len = strlen(name);
|
||||
if (len >= 0 && len < (MAX_FILENAME_LENGTH + 1))
|
||||
int len = name ? strlen(name) : 0;
|
||||
if (len > 0 && len < (MAX_FILENAME_LENGTH + 1))
|
||||
{
|
||||
command->m_type = CMD_PROFILE_TIMING;
|
||||
strcpy(command->m_profile.m_name, name);
|
||||
@@ -5290,6 +5290,7 @@ B3_SHARED_API b3SharedMemoryCommandHandle b3ProfileTimingCommandInit(b3PhysicsCl
|
||||
strcpy(command->m_profile.m_name, invalid);
|
||||
command->m_profile.m_name[len] = 0;
|
||||
}
|
||||
command->m_profile.m_type = -1;
|
||||
command->m_profile.m_durationInMicroSeconds = 0;
|
||||
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)
|
||||
{
|
||||
PhysicsClient* cl = (PhysicsClient*)physClient;
|
||||
|
||||
@@ -664,6 +664,7 @@ extern "C"
|
||||
|
||||
B3_SHARED_API b3SharedMemoryCommandHandle b3ProfileTimingCommandInit(b3PhysicsClientHandle physClient, const char* name);
|
||||
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 b3PopProfileTiming(b3PhysicsClientHandle physClient);
|
||||
|
||||
@@ -8037,44 +8037,35 @@ bool PhysicsServerCommandProcessor::processProfileTimingCommand(const struct Sha
|
||||
{
|
||||
bool hasStatus = true;
|
||||
|
||||
B3_PROFILE("custom"); //clientCmd.m_profile.m_name);
|
||||
|
||||
{
|
||||
B3_PROFILE("event"); //clientCmd.m_profile.m_name);
|
||||
char** eventNamePtr = m_data->m_profileEvents[clientCmd.m_profile.m_name];
|
||||
char* eventName = 0;
|
||||
if (eventNamePtr)
|
||||
{
|
||||
B3_PROFILE("reuse");
|
||||
eventName = *eventNamePtr;
|
||||
}
|
||||
else
|
||||
{
|
||||
B3_PROFILE("alloc");
|
||||
int len = strlen(clientCmd.m_profile.m_name);
|
||||
eventName = new char[len + 1];
|
||||
strcpy(eventName, clientCmd.m_profile.m_name);
|
||||
eventName[len] = 0;
|
||||
m_data->m_profileEvents.insert(eventName, eventName);
|
||||
}
|
||||
|
||||
if (clientCmd.m_profile.m_type == 0)
|
||||
{
|
||||
|
||||
char** eventNamePtr = m_data->m_profileEvents[clientCmd.m_profile.m_name];
|
||||
char* eventName = 0;
|
||||
if (eventNamePtr)
|
||||
{
|
||||
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);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
eventName = *eventNamePtr;
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
int len = strlen(clientCmd.m_profile.m_name);
|
||||
eventName = new char[len + 1];
|
||||
strcpy(eventName, clientCmd.m_profile.m_name);
|
||||
eventName[len] = 0;
|
||||
m_data->m_profileEvents.insert(eventName, eventName);
|
||||
}
|
||||
|
||||
b3EnterProfileZone(eventName);
|
||||
}
|
||||
if (clientCmd.m_profile.m_type == 1)
|
||||
{
|
||||
b3LeaveProfileZone();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
serverStatusOut.m_type = CMD_CLIENT_COMMAND_COMPLETED;
|
||||
|
||||
@@ -627,6 +627,7 @@ struct b3Profile
|
||||
{
|
||||
char m_name[MAX_FILENAME_LENGTH];
|
||||
int m_durationInMicroSeconds;
|
||||
int m_type;
|
||||
};
|
||||
|
||||
struct SdfLoadedArgs
|
||||
|
||||
Reference in New Issue
Block a user