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

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