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:
@@ -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);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -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);
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user