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
This commit is contained in:
Erwin Coumans 2017-09-02 11:35:54 -07:00
parent 8319fa0380
commit 3f21e528f0
3 changed files with 11 additions and 4 deletions

View File

@ -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);
}
}

View File

@ -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);
}
}

View File

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