From 1f64a87abeae41634f9b5f55b9ffeb9ceed63809 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Thu, 4 May 2017 17:51:40 -0700 Subject: [PATCH] Improve ChromeTraceUtil logging, allow filename to be specified. Expose this ChromeTraceUtil logging to C-API: start/statelogging and submitProfileTiming pybullet.submitProfileTiming, and STATE_LOGGING_PROFILE_TIMINGS used in startStateLogging added example for Python profileTiming.py and C++ b3RobotSimulatorClientAPI::submitProfileTiming --- .../ExampleBrowser/OpenGLExampleBrowser.cpp | 2 +- .../b3RobotSimulatorClientAPI.cpp | 33 +++++ .../b3RobotSimulatorClientAPI.h | 3 + examples/SharedMemory/PhysicsClientC_API.cpp | 36 +++++- examples/SharedMemory/PhysicsClientC_API.h | 2 + .../PhysicsServerCommandProcessor.cpp | 114 +++++++++++++++--- .../PhysicsServerSharedMemory.cpp | 2 +- examples/SharedMemory/SharedMemoryCommands.h | 9 ++ examples/SharedMemory/SharedMemoryPublic.h | 2 + .../StandaloneMain/hellovr_opengl_main.cpp | 4 +- examples/Utils/ChromeTraceUtil.cpp | 4 +- examples/Utils/ChromeTraceUtil.h | 2 +- examples/pybullet/examples/profileTiming.py | 12 ++ examples/pybullet/pybullet.c | 41 +++++++ src/Bullet3Common/b3HashMap.h | 12 ++ .../Dynamics/btDiscreteDynamicsWorld.cpp | 3 +- .../Featherstone/btMultiBodyDynamicsWorld.cpp | 2 +- 17 files changed, 255 insertions(+), 28 deletions(-) create mode 100644 examples/pybullet/examples/profileTiming.py diff --git a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp index 9bbcafb64..cdfef5404 100644 --- a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp +++ b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp @@ -260,7 +260,7 @@ void MyKeyboardCallback(int key, int state) } else { - b3ChromeUtilsStopTimingsAndWriteJsonFile(); + b3ChromeUtilsStopTimingsAndWriteJsonFile("timings"); } #endif //BT_NO_PROFILE } diff --git a/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp b/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp index 17a4806cc..5e4eefa74 100644 --- a/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp +++ b/examples/RobotSimulator/b3RobotSimulatorClientAPI.cpp @@ -912,6 +912,11 @@ void b3RobotSimulatorClientAPI::getKeyboardEvents(b3KeyboardEventsData* keyboard int b3RobotSimulatorClientAPI::startStateLogging(b3StateLoggingType loggingType, const std::string& fileName, const b3AlignedObjectArray& objectUniqueIds, int maxLogDof) { + if (!isConnected()) + { + b3Warning("Not connected"); + return -1; + } int loggingUniqueId = -1; b3SharedMemoryCommandHandle commandHandle; commandHandle = b3StateLoggingCommandInit(m_data->m_physicsClientHandle); @@ -942,6 +947,12 @@ int b3RobotSimulatorClientAPI::startStateLogging(b3StateLoggingType loggingType, void b3RobotSimulatorClientAPI::stopStateLogging(int stateLoggerUniqueId) { + if (!isConnected()) + { + b3Warning("Not connected"); + return; + } + b3SharedMemoryCommandHandle commandHandle; b3SharedMemoryStatusHandle statusHandle; commandHandle = b3StateLoggingCommandInit(m_data->m_physicsClientHandle); @@ -951,6 +962,12 @@ void b3RobotSimulatorClientAPI::stopStateLogging(int stateLoggerUniqueId) void b3RobotSimulatorClientAPI::resetDebugVisualizerCamera(double cameraDistance, double cameraPitch, double cameraYaw, const b3Vector3& targetPos) { + if (!isConnected()) + { + b3Warning("Not connected"); + return; + } + b3SharedMemoryCommandHandle commandHandle = b3InitConfigureOpenGLVisualizer(m_data->m_physicsClientHandle); if (commandHandle) { @@ -963,3 +980,19 @@ void b3RobotSimulatorClientAPI::resetDebugVisualizerCamera(double cameraDistance b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle); } } + +void b3RobotSimulatorClientAPI::submitProfileTiming(const std::string& profileName, int durationInMicroSeconds) +{ + if (!isConnected()) + { + b3Warning("Not connected"); + return; + } + + b3SharedMemoryCommandHandle commandHandle = b3ProfileTimingCommandInit(m_data->m_physicsClientHandle, profileName.c_str()); + if (durationInMicroSeconds>=0) + { + b3SetProfileTimingDuractionInMicroSeconds(commandHandle, durationInMicroSeconds); + } + b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle); +} \ No newline at end of file diff --git a/examples/RobotSimulator/b3RobotSimulatorClientAPI.h b/examples/RobotSimulator/b3RobotSimulatorClientAPI.h index f92fd6497..7dd9fdeb4 100644 --- a/examples/RobotSimulator/b3RobotSimulatorClientAPI.h +++ b/examples/RobotSimulator/b3RobotSimulatorClientAPI.h @@ -210,6 +210,9 @@ public: void getVREvents(b3VREventsData* vrEventsData, int deviceTypeFilter); void getKeyboardEvents(b3KeyboardEventsData* keyboardEventsData); + + void submitProfileTiming(const std::string& profileName, int durationInMicroSeconds=1); + }; #endif //B3_ROBOT_SIMULATOR_CLIENT_API_H diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 150c6a242..7fb2fb30a 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -2695,6 +2695,41 @@ void b3GetKeyboardEventsData(b3PhysicsClientHandle physClient, struct b3Keyboard } +b3SharedMemoryCommandHandle b3ProfileTimingCommandInit(b3PhysicsClientHandle physClient, const char* name) +{ + PhysicsClient* cl = (PhysicsClient*)physClient; + b3Assert(cl); + b3Assert(cl->canSubmitCommand()); + struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); + b3Assert(command); + + int len = strlen(name); + if (len>=0 && len < (MAX_FILENAME_LENGTH+1)) + { + command->m_type = CMD_PROFILE_TIMING; + strcpy(command->m_profile.m_name,name); + command->m_profile.m_name[len]=0; + } else + { + const char* invalid = "InvalidProfileTimingName"; + int len = strlen(invalid); + strcpy(command->m_profile.m_name,invalid); + command->m_profile.m_name[len] = 0; + } + command->m_profile.m_durationInMicroSeconds = 0; + return (b3SharedMemoryCommandHandle)command; +} + +void b3SetProfileTimingDuractionInMicroSeconds(b3SharedMemoryCommandHandle commandHandle, int duration) +{ + 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_durationInMicroSeconds = duration; + } +} b3SharedMemoryCommandHandle b3StateLoggingCommandInit(b3PhysicsClientHandle physClient) { @@ -2841,7 +2876,6 @@ int b3StateLoggingSetDeviceTypeFilter(b3SharedMemoryCommandHandle commandHandle, return 0; } - int b3StateLoggingStop(b3SharedMemoryCommandHandle commandHandle, int loggingUid) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index 61db28054..482c6f4d4 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -392,6 +392,8 @@ int b3GetStatusLoggingUniqueId(b3SharedMemoryStatusHandle statusHandle); int b3StateLoggingStop(b3SharedMemoryCommandHandle commandHandle, int loggingUniqueId); +b3SharedMemoryCommandHandle b3ProfileTimingCommandInit(b3PhysicsClientHandle physClient, const char* name); +void b3SetProfileTimingDuractionInMicroSeconds(b3SharedMemoryCommandHandle commandHandle, int duration); void b3SetTimeOut(b3PhysicsClientHandle physClient, double timeOutInSeconds); double b3GetTimeOut(b3PhysicsClientHandle physClient); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 8ea61307b..30672dae5 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -13,7 +13,9 @@ #include "BulletDynamics/Featherstone/btMultiBodySliderConstraint.h" #include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h" #include "BulletCollision/NarrowPhaseCollision/btPersistentManifold.h" -#include "LinearMath/btHashMap.h" +#include "Bullet3Common/b3HashMap.h" +#include "../Utils/ChromeTraceUtil.h" + #include "BulletInverseDynamics/MultiBodyTree.hpp" #include "IKTrajectoryHelper.h" #include "btBulletDynamicsCommon.h" @@ -28,7 +30,7 @@ #include "SharedMemoryCommands.h" #include "LinearMath/btRandom.h" #include "Bullet3Common/b3ResizablePool.h" - +#include "../Utils/b3Clock.h" #ifdef B3_ENABLE_TINY_AUDIO #include "../TinyAudio/b3SoundEngine.h" #endif @@ -132,7 +134,7 @@ struct InteralBodyData btTransform m_rootLocalInertialFrame; btAlignedObjectArray m_linkLocalInertialFrames; #ifdef B3_ENABLE_TINY_AUDIO - btHashMap m_audioSources; + b3HashMap m_audioSources; #endif //B3_ENABLE_TINY_AUDIO InteralBodyData() @@ -1158,11 +1160,11 @@ struct PhysicsServerCommandProcessorInternalData btScalar m_physicsDeltaTime; btScalar m_numSimulationSubSteps; btAlignedObjectArray m_multiBodyJointFeedbacks; - btHashMap m_inverseDynamicsBodies; - btHashMap m_inverseKinematicsHelpers; + b3HashMap m_inverseDynamicsBodies; + b3HashMap m_inverseKinematicsHelpers; int m_userConstraintUIDGenerator; - btHashMap m_userConstraints; + b3HashMap m_userConstraints; b3AlignedObjectArray m_saveWorldBodyData; @@ -1198,6 +1200,8 @@ struct PhysicsServerCommandProcessorInternalData btAlignedObjectArray m_stateLoggers; int m_stateLoggersUniqueId; + int m_profileTimingLoggingUid; + std::string m_profileTimingFileName; struct GUIHelperInterface* m_guiHelper; int m_sharedMemoryKey; @@ -1219,6 +1223,8 @@ struct PhysicsServerCommandProcessorInternalData b3SoundEngine m_soundEngine; #endif + b3HashMap m_profileEvents; + PhysicsServerCommandProcessorInternalData() : m_allowRealTimeSimulation(false), @@ -1247,6 +1253,7 @@ struct PhysicsServerCommandProcessorInternalData m_dynamicsWorld(0), m_remoteDebugDrawer(0), m_stateLoggersUniqueId(0), + m_profileTimingLoggingUid(-1), m_guiHelper(0), m_sharedMemoryKey(SHARED_MEMORY_KEY), m_verboseOutput(false), @@ -1372,7 +1379,11 @@ PhysicsServerCommandProcessor::~PhysicsServerCommandProcessor() delete m_data->m_commandLogger; m_data->m_commandLogger = 0; } - + for (int i=0;im_profileEvents.size();i++) + { + char* event = *m_data->m_profileEvents.getAtIndex(i); + delete[] event; + } delete m_data; } @@ -2210,7 +2221,7 @@ int PhysicsServerCommandProcessor::createBodyInfoStream(int bodyUniqueId, char* bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes ) { - BT_PROFILE("processCommand"); +// BT_PROFILE("processCommand"); bool hasStatus = false; @@ -2278,7 +2289,18 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm if (clientCmd.m_updateFlags & STATE_LOGGING_START_LOG) { - + if (clientCmd.m_stateLoggingArguments.m_logType == STATE_LOGGING_PROFILE_TIMINGS) + { + if (m_data->m_profileTimingLoggingUid<0) + { + b3ChromeUtilsStartTimings(); + m_data->m_profileTimingFileName = clientCmd.m_stateLoggingArguments.m_fileName; + int loggerUid = m_data->m_stateLoggersUniqueId++; + serverStatusOut.m_type = CMD_STATE_LOGGING_START_COMPLETED; + serverStatusOut.m_stateLoggingResultArgs.m_loggingUniqueId = loggerUid; + m_data->m_profileTimingLoggingUid = loggerUid; + } + } if (clientCmd.m_stateLoggingArguments.m_logType == STATE_LOGGING_VIDEO_MP4) { //if (clientCmd.m_stateLoggingArguments.m_fileName) @@ -2416,14 +2438,22 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm } if ((clientCmd.m_updateFlags & STATE_LOGGING_STOP_LOG) && clientCmd.m_stateLoggingArguments.m_loggingUniqueId>=0) { - serverStatusOut.m_type = CMD_STATE_LOGGING_COMPLETED; - for (int i=0;im_stateLoggers.size();i++) + if (clientCmd.m_stateLoggingArguments.m_loggingUniqueId == m_data->m_profileTimingLoggingUid) { - if (m_data->m_stateLoggers[i]->m_loggingUniqueId==clientCmd.m_stateLoggingArguments.m_loggingUniqueId) + b3ChromeUtilsStopTimingsAndWriteJsonFile(m_data->m_profileTimingFileName.c_str()); + m_data->m_profileTimingLoggingUid = -1; + } + else + { + serverStatusOut.m_type = CMD_STATE_LOGGING_COMPLETED; + for (int i=0;im_stateLoggers.size();i++) { - m_data->m_stateLoggers[i]->stop(); - delete m_data->m_stateLoggers[i]; - m_data->m_stateLoggers.removeAtIndex(i); + if (m_data->m_stateLoggers[i]->m_loggingUniqueId==clientCmd.m_stateLoggingArguments.m_loggingUniqueId) + { + m_data->m_stateLoggers[i]->stop(); + delete m_data->m_stateLoggers[i]; + m_data->m_stateLoggers.removeAtIndex(i); + } } } } @@ -2458,7 +2488,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm } case CMD_REQUEST_VR_EVENTS_DATA: { - BT_PROFILE("CMD_REQUEST_VR_EVENTS_DATA"); + //BT_PROFILE("CMD_REQUEST_VR_EVENTS_DATA"); serverStatusOut.m_sendVREvents.m_numVRControllerEvents = 0; for (int i=0;im_keyboardEvents.size(); if (serverStatusOut.m_sendKeyboardEvents.m_numKeyboardEvents>MAX_KEYBOARD_EVENTS) @@ -3320,6 +3350,56 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm break; } + case CMD_PROFILE_TIMING: + { + { + 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); + + } + + + { + { + 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); + } + } + } + } + } + } + } + } + serverStatusOut.m_type = CMD_CLIENT_COMMAND_COMPLETED; + hasStatus = true; + break; + } + case CMD_SEND_DESIRED_STATE: { BT_PROFILE("CMD_SEND_DESIRED_STATE"); diff --git a/examples/SharedMemory/PhysicsServerSharedMemory.cpp b/examples/SharedMemory/PhysicsServerSharedMemory.cpp index dde91f028..0a9c75f3c 100644 --- a/examples/SharedMemory/PhysicsServerSharedMemory.cpp +++ b/examples/SharedMemory/PhysicsServerSharedMemory.cpp @@ -252,7 +252,7 @@ void PhysicsServerSharedMemory::processClientCommands() if (m_data->m_testBlocks[block]->m_numClientCommands> m_data->m_testBlocks[block]->m_numProcessedClientCommands) { - BT_PROFILE("processClientCommand"); + //BT_PROFILE("processClientCommand"); //until we implement a proper ring buffer, we assume always maximum of 1 outstanding commands btAssert(m_data->m_testBlocks[block]->m_numClientCommands==m_data->m_testBlocks[block]->m_numProcessedClientCommands+1); diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 299b1c804..c0a7a3315 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -459,6 +459,14 @@ struct b3ObjectArgs int m_userConstraintUniqueIds[MAX_SDF_BODIES]; }; +struct b3Profile +{ + char m_name[MAX_FILENAME_LENGTH]; + int m_durationInMicroSeconds; +}; + + + struct SdfLoadedArgs { int m_numBodies; @@ -758,6 +766,7 @@ struct SharedMemoryCommand struct StateLoggingRequest m_stateLoggingArguments; struct ConfigureOpenGLVisualizerRequest m_configureOpenGLVisualizerArguments; struct b3ObjectArgs m_removeObjectArgs; + struct b3Profile m_profile; }; }; diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index 57b44fef6..410ca5d3e 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -57,6 +57,7 @@ enum EnumSharedMemoryClientCommand CMD_REQUEST_OPENGL_VISUALIZER_CAMERA, CMD_REMOVE_BODY, CMD_RESET_DYNAMIC_INFO, + CMD_PROFILE_TIMING, //don't go beyond this command! CMD_MAX_CLIENT_COMMANDS, @@ -388,6 +389,7 @@ enum b3StateLoggingType STATE_LOGGING_VIDEO_MP4 = 3, STATE_LOGGING_COMMANDS = 4, STATE_LOGGING_CONTACT_POINTS = 5, + STATE_LOGGING_PROFILE_TIMINGS = 6, }; diff --git a/examples/StandaloneMain/hellovr_opengl_main.cpp b/examples/StandaloneMain/hellovr_opengl_main.cpp index 4965e7df5..518fc98e8 100644 --- a/examples/StandaloneMain/hellovr_opengl_main.cpp +++ b/examples/StandaloneMain/hellovr_opengl_main.cpp @@ -355,7 +355,7 @@ void MyKeyboardCallback(int key, int state) } else { - b3ChromeUtilsStopTimingsAndWriteJsonFile(); + b3ChromeUtilsStopTimingsAndWriteJsonFile("timings"); } } if (sExample) @@ -2342,7 +2342,7 @@ int main(int argc, char *argv[]) if (args.CheckCmdLineFlag("tracing")) { - b3ChromeUtilsStopTimingsAndWriteJsonFile(); + b3ChromeUtilsStopTimingsAndWriteJsonFile("timings"); } diff --git a/examples/Utils/ChromeTraceUtil.cpp b/examples/Utils/ChromeTraceUtil.cpp index 35faa1957..80139719f 100644 --- a/examples/Utils/ChromeTraceUtil.cpp +++ b/examples/Utils/ChromeTraceUtil.cpp @@ -239,7 +239,7 @@ void b3ChromeUtilsStartTimings() btSetCustomLeaveProfileZoneFunc(MyLeaveProfileZoneFunc); } -void b3ChromeUtilsStopTimingsAndWriteJsonFile() +void b3ChromeUtilsStopTimingsAndWriteJsonFile(const char* fileNamePrefix) { b3SetCustomEnterProfileZoneFunc(MyDummyEnterProfileZoneFunc); b3SetCustomLeaveProfileZoneFunc(MyDummyLeaveProfileZoneFunc); @@ -248,7 +248,7 @@ void b3ChromeUtilsStopTimingsAndWriteJsonFile() btSetCustomLeaveProfileZoneFunc(MyDummyLeaveProfileZoneFunc); char fileName[1024]; static int fileCounter = 0; - sprintf(fileName,"timings_%d.json",fileCounter++); + sprintf(fileName,"%s_%d.json",fileNamePrefix, fileCounter++); gTimingFile = fopen(fileName,"w"); fprintf(gTimingFile,"{\"traceEvents\":[\n"); //dump the content to file diff --git a/examples/Utils/ChromeTraceUtil.h b/examples/Utils/ChromeTraceUtil.h index 27cc3ab22..b1cf8d3b2 100644 --- a/examples/Utils/ChromeTraceUtil.h +++ b/examples/Utils/ChromeTraceUtil.h @@ -3,7 +3,7 @@ #define B3_CHROME_TRACE_UTIL_H void b3ChromeUtilsStartTimings(); -void b3ChromeUtilsStopTimingsAndWriteJsonFile(); +void b3ChromeUtilsStopTimingsAndWriteJsonFile(const char* fileNamePrefix); void b3ChromeUtilsEnableProfiling(); #endif//B3_CHROME_TRACE_UTIL_H \ No newline at end of file diff --git a/examples/pybullet/examples/profileTiming.py b/examples/pybullet/examples/profileTiming.py new file mode 100644 index 000000000..7b761fc9b --- /dev/null +++ b/examples/pybullet/examples/profileTiming.py @@ -0,0 +1,12 @@ +import pybullet as p +import time + +p.connect(p.GUI) + +t = time.time()+0.1 + +logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "haha") +while (time.time()=0) + { + b3SetProfileTimingDuractionInMicroSeconds(commandHandle, duractionInMicroSeconds); + } + b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + } + Py_INCREF(Py_None); + return Py_None; +} + + static PyObject* pybullet_stopStateLogging(PyObject* self, PyObject* args, PyObject* keywds) { b3SharedMemoryStatusHandle statusHandle; @@ -5691,6 +5727,10 @@ static PyMethodDef SpamMethods[] = { "Cast a batch of rays and return the result for each of the rays (first object hit, if any. or -1) " "Takes two arguments (list of from_positions [x,y,z] and a list of to_positions [x,y,z] in Cartesian world coordinates"}, + {"submitProfileTiming", (PyCFunction)pybullet_submitProfileTiming, METH_VARARGS | METH_KEYWORDS, + "Add a custom profile timing that will be visible in performance profile recordings on the physics server." + "On the physics server (in GUI and VR mode) you can press 'p' to start and/or stop profile recordings" }, + {"setTimeOut", (PyCFunction)pybullet_setTimeOut, METH_VARARGS | METH_KEYWORDS, "Set the timeOut in seconds, used for most of the API calls."}, // todo(erwincoumans) @@ -5821,6 +5861,7 @@ initpybullet(void) PyModule_AddIntConstant(m, "STATE_LOGGING_VR_CONTROLLERS", STATE_LOGGING_VR_CONTROLLERS); PyModule_AddIntConstant(m, "STATE_LOGGING_VIDEO_MP4", STATE_LOGGING_VIDEO_MP4); PyModule_AddIntConstant(m, "STATE_LOGGING_CONTACT_POINTS", STATE_LOGGING_CONTACT_POINTS); + PyModule_AddIntConstant(m, "STATE_LOGGING_PROFILE_TIMINGS", STATE_LOGGING_PROFILE_TIMINGS); PyModule_AddIntConstant(m, "COV_ENABLE_GUI", COV_ENABLE_GUI); PyModule_AddIntConstant(m, "COV_ENABLE_SHADOWS", COV_ENABLE_SHADOWS); diff --git a/src/Bullet3Common/b3HashMap.h b/src/Bullet3Common/b3HashMap.h index dc3579117..ceeb838e2 100644 --- a/src/Bullet3Common/b3HashMap.h +++ b/src/Bullet3Common/b3HashMap.h @@ -399,6 +399,18 @@ protected: return &m_valueArray[index]; } + Key getKeyAtIndex(int index) + { + b3Assert(index < m_keyArray.size()); + return m_keyArray[index]; + } + + const Key getKeyAtIndex(int index) const + { + b3Assert(index < m_keyArray.size()); + return m_keyArray[index]; + } + Value* operator[](const Key& key) { return find(key); } diff --git a/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp b/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp index d420cd29c..27bb88f2a 100644 --- a/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp +++ b/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp @@ -374,7 +374,7 @@ void btDiscreteDynamicsWorld::synchronizeSingleMotionState(btRigidBody* body) void btDiscreteDynamicsWorld::synchronizeMotionStates() { - BT_PROFILE("synchronizeMotionStates"); +// BT_PROFILE("synchronizeMotionStates"); if (m_synchronizeAllMotionStates) { //iterate over all collision objects @@ -402,7 +402,6 @@ int btDiscreteDynamicsWorld::stepSimulation( btScalar timeStep,int maxSubSteps, { startProfiling(timeStep); - BT_PROFILE("stepSimulation"); int numSimulationSubSteps = 0; diff --git a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp index 20b6a04b3..2bed4a3a7 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp @@ -917,7 +917,7 @@ void btMultiBodyDynamicsWorld::clearMultiBodyConstraintForces() void btMultiBodyDynamicsWorld::clearMultiBodyForces() { { - BT_PROFILE("clearMultiBodyForces"); + // BT_PROFILE("clearMultiBodyForces"); for (int i=0;im_multiBodies.size();i++) { btMultiBody* bod = m_multiBodies[i];