From 09caa599ff0ae8b9447c898b1e2f3a47b321d59d Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Fri, 5 May 2017 10:38:16 -0700 Subject: [PATCH 1/2] avoid an assert when removing a non-existing graphics index in debug mode --- examples/ExampleBrowser/OpenGLGuiHelper.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.cpp b/examples/ExampleBrowser/OpenGLGuiHelper.cpp index b26dfbf59..5c0e995af 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.cpp +++ b/examples/ExampleBrowser/OpenGLGuiHelper.cpp @@ -243,7 +243,10 @@ void OpenGLGuiHelper::removeAllGraphicsInstances() void OpenGLGuiHelper::removeGraphicsInstance(int graphicsUid) { - m_data->m_glApp->m_renderer->removeGraphicsInstance(graphicsUid); + if (graphicsUid>=0) + { + m_data->m_glApp->m_renderer->removeGraphicsInstance(graphicsUid); + }; } From 385156cbc5d1a54bdc997f3556825434087a10a1 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Fri, 5 May 2017 17:24:35 -0700 Subject: [PATCH 2/2] add simple humanoid_benchmark.py and mjcf file --- data/mjcf/humanoid_symmetric.xml | 118 ++++++++++++++++++ .../pybullet/examples/humanoid_benchmark.py | 20 +++ 2 files changed, 138 insertions(+) create mode 100644 data/mjcf/humanoid_symmetric.xml create mode 100644 examples/pybullet/examples/humanoid_benchmark.py diff --git a/data/mjcf/humanoid_symmetric.xml b/data/mjcf/humanoid_symmetric.xml new file mode 100644 index 000000000..de2fee3f5 --- /dev/null +++ b/data/mjcf/humanoid_symmetric.xml @@ -0,0 +1,118 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/pybullet/examples/humanoid_benchmark.py b/examples/pybullet/examples/humanoid_benchmark.py new file mode 100644 index 000000000..2a9c0cf68 --- /dev/null +++ b/examples/pybullet/examples/humanoid_benchmark.py @@ -0,0 +1,20 @@ +import pybullet as p +import time +p.connect(p.GUI) +p.setGravity(0,0,-10) +p.setPhysicsEngineParameter(numSolverIterations=5) +p.loadMJCF("mjcf/humanoid.xml") + +#first let the humanoid fall +p.setRealTimeSimulation(1) +time.sleep(3) +p.setRealTimeSimulation(0) + +#now do a benchmark +print("Starting benchmark") +logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS,"pybullet_humanoid_timings.json") +for i in range(1000): + p.stepSimulation() +p.stopStateLogging(logId) + +print("ended benchmark") \ No newline at end of file