improve pybullet performance of loadURDF/SDF/MJCF and 'createCollisionShape'/'createMultiBody' for GUI/VR/SHARED_MEMORY,

use p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0) before loading and
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1) afterwards
This commit is contained in:
Erwin Coumans 2017-07-14 23:12:16 +01:00
parent b63023c692
commit 0df8887990
7 changed files with 58 additions and 27 deletions

View File

@ -230,6 +230,7 @@ static double gMinUpdateTimeMicroSecs = 4000.;
void ExampleBrowserThreadFunc(void* userPtr,void* lsMemory)
{
printf("ExampleBrowserThreadFunc started\n");
ExampleBrowserThreadLocalStorage* localStorage = (ExampleBrowserThreadLocalStorage*) lsMemory;
@ -257,7 +258,9 @@ void ExampleBrowserThreadFunc(void* userPtr,void* lsMemory)
do
{
B3_PROFILE("ExampleBrowserThreadFunc");
clock.usleep(0);
//B3_PROFILE("ExampleBrowserThreadFunc");
float deltaTimeInSeconds = clock.getTimeMicroseconds()/1000000.f;
{
if (deltaTimeInSeconds > 0.1)
@ -266,13 +269,13 @@ void ExampleBrowserThreadFunc(void* userPtr,void* lsMemory)
}
if (deltaTimeInSeconds < (gMinUpdateTimeMicroSecs/1e6))
{
B3_PROFILE("clock.usleep");
clock.usleep(gMinUpdateTimeMicroSecs/10.);
//B3_PROFILE("clock.usleep");
exampleBrowser->updateGraphics();
} else
{
B3_PROFILE("exampleBrowser->update");
//B3_PROFILE("exampleBrowser->update");
clock.reset();
exampleBrowser->updateGraphics();
exampleBrowser->update(deltaTimeInSeconds);
}
}
@ -429,6 +432,7 @@ void btUpdateInProcessExampleBrowserMainThread(btInProcessExampleBrowserMainThre
{
float deltaTimeInSeconds = data->m_clock.getTimeMicroseconds()/1000000.f;
data->m_clock.reset();
data->m_exampleBrowser->updateGraphics();
data->m_exampleBrowser->update(deltaTimeInSeconds);
}
void btShutDownExampleBrowserMainThread(btInProcessExampleBrowserMainThreadInternalData* data)

View File

@ -127,6 +127,8 @@ extern bool useShadowMap;
bool visualWireframe=false;
static bool renderVisualGeometry=true;
static bool renderGrid = true;
static bool gEnableRenderLoop = true;
bool renderGui = true;
static bool enable_experimental_opencl = false;
@ -370,6 +372,10 @@ void OpenGLExampleBrowser::registerFileImporter(const char* extension, CommonExa
void OpenGLExampleBrowserVisualizerFlagCallback(int flag, bool enable)
{
if (flag == COV_ENABLE_RENDERING)
{
gEnableRenderLoop = (enable!=0);
}
if (flag == COV_ENABLE_SHADOWS)
{
useShadowMap = enable;
@ -1185,7 +1191,7 @@ void OpenGLExampleBrowser::updateGraphics()
{
if (!pauseSimulation || singleStepSimulation)
{
B3_PROFILE("sCurrentDemo->updateGraphics");
//B3_PROFILE("sCurrentDemo->updateGraphics");
sCurrentDemo->updateGraphics();
}
}
@ -1193,6 +1199,9 @@ void OpenGLExampleBrowser::updateGraphics()
void OpenGLExampleBrowser::update(float deltaTime)
{
if (!gEnableRenderLoop)
return;
b3ChromeUtilsEnableProfiling();
B3_PROFILE("OpenGLExampleBrowser::update");

View File

@ -4,6 +4,7 @@
#include "PhysicsClientSharedMemory.h"
#include"../ExampleBrowser/InProcessExampleBrowser.h"
#include <stdio.h>
#include "PhysicsServerExampleBullet2.h"
@ -52,12 +53,12 @@ public:
}
}
{
unsigned long int ms = m_clock.getTimeMilliseconds();
if (ms>20)
//unsigned long int ms = m_clock.getTimeMilliseconds();
//if (ms>2)
{
B3_PROFILE("m_clock.reset()");
// B3_PROFILE("m_clock.reset()");
m_clock.reset();
// m_clock.reset();
btUpdateInProcessExampleBrowserMainThread(m_data);
}
}
@ -165,7 +166,8 @@ public:
// return non-null if there is a status, nullptr otherwise
virtual const struct SharedMemoryStatus* processServerStatus()
{
//m_physicsServerExample->updateGraphics();
printf("updating graphics!\n");
m_physicsServerExample->updateGraphics();
unsigned long long int curTime = m_clock.getTimeMicroseconds();
unsigned long long int dtMicro = curTime - m_prevTime;

View File

@ -4,7 +4,8 @@
#define SHARED_MEMORY_KEY 12347
///increase the SHARED_MEMORY_MAGIC_NUMBER whenever incompatible changes are made in the structures
///my convention is year/month/day/rev
#define SHARED_MEMORY_MAGIC_NUMBER 201706015
#define SHARED_MEMORY_MAGIC_NUMBER 201707140
//#define SHARED_MEMORY_MAGIC_NUMBER 201706015
//#define SHARED_MEMORY_MAGIC_NUMBER 201706001
//#define SHARED_MEMORY_MAGIC_NUMBER 201703024

View File

@ -373,8 +373,8 @@ void MyKeyboardCallback(int key, int state)
#include "../SharedMemory/SharedMemoryPublic.h"
extern bool useShadowMap;
bool gEnableVRRenderControllers=true;
static bool gEnableVRRenderControllers=true;
static bool gEnableVRRendering = true;
void VRPhysicsServerVisualizerFlagCallback(int flag, bool enable)
@ -391,7 +391,10 @@ void VRPhysicsServerVisualizerFlagCallback(int flag, bool enable)
{
gEnableVRRenderControllers = enable;
}
if (flag == COV_ENABLE_RENDERING)
{
gEnableVRRendering = enable;
}
if (flag == COV_ENABLE_WIREFRAME)
@ -887,13 +890,18 @@ void CMainApplication::RunMainLoop()
while ( !bQuit && !m_app->m_window->requestedExit())
{
b3ChromeUtilsEnableProfiling();
if (gEnableVRRendering)
{
B3_PROFILE("main");
B3_PROFILE("main");
bQuit = HandleInput();
bQuit = HandleInput();
RenderFrame();
}
RenderFrame();
} else
{
b3Clock::usleep(0);
sExample->updateGraphics();
}
}
}

View File

@ -250,18 +250,25 @@ void b3ChromeUtilsStopTimingsAndWriteJsonFile(const char* fileNamePrefix)
static int fileCounter = 0;
sprintf(fileName,"%s_%d.json",fileNamePrefix, fileCounter++);
gTimingFile = fopen(fileName,"w");
fprintf(gTimingFile,"{\"traceEvents\":[\n");
//dump the content to file
for (int i=0;i<BT_QUICKPROF_MAX_THREAD_COUNT;i++)
if (gTimingFile)
{
if (gTimings[i].m_numTimings)
fprintf(gTimingFile,"{\"traceEvents\":[\n");
//dump the content to file
for (int i=0;i<BT_QUICKPROF_MAX_THREAD_COUNT;i++)
{
printf("Writing %d timings for thread %d\n", gTimings[i].m_numTimings, i);
gTimings[i].flush();
if (gTimings[i].m_numTimings)
{
printf("Writing %d timings for thread %d\n", gTimings[i].m_numTimings, i);
gTimings[i].flush();
}
}
fprintf(gTimingFile,"\n],\n\"displayTimeUnit\": \"ns\"}");
fclose(gTimingFile);
} else
{
b3Printf("Error opening file");
b3Printf(fileName);
}
fprintf(gTimingFile,"\n],\n\"displayTimeUnit\": \"ns\"}");
fclose(gTimingFile);
gTimingFile = 0;
}

View File

@ -420,7 +420,7 @@ else:
setup(
name = 'pybullet',
version='1.2.1',
version='1.2.2',
description='Official Python Interface for the Bullet Physics SDK Robotics Simulator',
long_description='pybullet is an easy to use Python module for physics simulation, robotics and machine learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.',
url='https://github.com/bulletphysics/bullet3',