From 3f21e528f0b79eb00303ab915bf249e126fb2f22 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Sat, 2 Sep 2017 11:35:54 -0700 Subject: [PATCH] revert name 'v' -> 'u' (backward compatibility) and 'u' -> 't' make vr_kuka_setup.py load faster, by disabling rendering during loading allow to setRealTimeSimulation(0) in VR --- examples/SharedMemory/PhysicsServerCommandProcessor.cpp | 4 ++-- examples/SharedMemory/PhysicsServerExample.cpp | 6 +++++- examples/pybullet/examples/vr_kuka_setup.py | 5 ++++- 3 files changed, 11 insertions(+), 4 deletions(-) diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 3ed0f5b5a..4877ff95b 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -890,7 +890,7 @@ struct GenericRobotStateLogger : public InternalStateLogger { m_structTypes.append("f"); char jointName[256]; - sprintf(jointName,"v%d",i); + sprintf(jointName,"u%d",i); structNames.push_back(jointName); } @@ -900,7 +900,7 @@ struct GenericRobotStateLogger : public InternalStateLogger { m_structTypes.append("f"); char jointName[256]; - sprintf(jointName,"u%d",i); + sprintf(jointName,"t%d",i); structNames.push_back(jointName); } } diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index 80968c880..208eeafe4 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -25,6 +25,8 @@ bool gEnablePicking=true; bool gEnableTeleporting=true; bool gEnableRendering= true; +bool gActivedVRRealTimeSimulation = false; + bool gEnableSyncPhysicsRendering= true; bool gEnableUpdateDebugDrawLines = true; static int gCamVisualizerWidth = 320; @@ -2627,8 +2629,10 @@ void PhysicsServerExample::renderScene() if (m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->isVRCamera()) { - if (!m_physicsServer.isRealTimeSimulationEnabled()) + if (!m_physicsServer.isRealTimeSimulationEnabled() && !gActivedVRRealTimeSimulation) { + //only activate real-time simulation once (for backward compatibility) + gActivedVRRealTimeSimulation = true; m_physicsServer.enableRealTimeSimulation(1); } } diff --git a/examples/pybullet/examples/vr_kuka_setup.py b/examples/pybullet/examples/vr_kuka_setup.py index 6d851c438..5362fa38d 100644 --- a/examples/pybullet/examples/vr_kuka_setup.py +++ b/examples/pybullet/examples/vr_kuka_setup.py @@ -5,7 +5,8 @@ cid = p.connect(p.SHARED_MEMORY) if (cid<0): p.connect(p.GUI) p.resetSimulation() - +#disable rendering during loading makes it much faster +p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0) objects = [p.loadURDF("plane.urdf", 0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,1.000000)] objects = [p.loadURDF("samurai.urdf", 0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,1.000000)] objects = [p.loadURDF("pr2_gripper.urdf", 0.500000,0.300006,0.700000,-0.000000,-0.000000,-0.000031,1.000000)] @@ -74,6 +75,8 @@ jointPositions=[ 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.0 for jointIndex in range (p.getNumJoints(ob)): p.resetJointState(ob,jointIndex,jointPositions[jointIndex]) +p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1) + p.setGravity(0.000000,0.000000,0.000000) p.setGravity(0,0,-10)