Merge pull request #2350 from erwincoumans/master

improved for inserting profile timings from Python, to analyzer performance
This commit is contained in:
erwincoumans
2019-08-01 21:22:27 -07:00
committed by GitHub
6 changed files with 66 additions and 50 deletions

View File

@@ -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;

View File

@@ -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);

View File

@@ -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;

View File

@@ -627,6 +627,7 @@ struct b3Profile
{
char m_name[MAX_FILENAME_LENGTH];
int m_durationInMicroSeconds;
int m_type;
};
struct SdfLoadedArgs

View File

@@ -1,11 +1,21 @@
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")
for i in range (100):
p.submitProfileTiming("deep_nested")
p.submitProfileTiming()
time.sleep(1./1000.)
p.submitProfileTiming()
p.submitProfileTiming()
p.stopStateLogging(logId)

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;
}