tweak color of quadruped robot URDF, tweak quadruped.py script to make it more compatible with VR demo
allow VR physics server to run with or without 'realTimeSimulation'
This commit is contained in:
@@ -4030,6 +4030,12 @@ int gDroppedSimulationSteps = 0;
|
||||
int gNumSteps = 0;
|
||||
double gDtInSec = 0.f;
|
||||
double gSubStep = 0.f;
|
||||
|
||||
void PhysicsServerCommandProcessor::enableRealTimeSimulation(bool enableRealTimeSim)
|
||||
{
|
||||
m_data->m_allowRealTimeSimulation = enableRealTimeSim;
|
||||
}
|
||||
|
||||
void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
|
||||
{
|
||||
if (gResetSimulation)
|
||||
@@ -4038,7 +4044,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
|
||||
gResetSimulation = false;
|
||||
}
|
||||
|
||||
if ((gEnableRealTimeSimVR || m_data->m_allowRealTimeSimulation) && m_data->m_guiHelper)
|
||||
if ((m_data->m_allowRealTimeSimulation) && m_data->m_guiHelper)
|
||||
{
|
||||
|
||||
///this hardcoded C++ scene creation is temporary for demo purposes. It will be done in Python later...
|
||||
|
||||
@@ -85,6 +85,7 @@ public:
|
||||
void replayFromLogFile(const char* fileName);
|
||||
void replayLogCommand(char* bufferServerToClient, int bufferSizeInBytes );
|
||||
void stepSimulationRealTime(double dtInSec);
|
||||
void enableRealTimeSimulation(bool enableRealTimeSim);
|
||||
void applyJointDamping(int bodyUniqueId);
|
||||
};
|
||||
|
||||
|
||||
@@ -1584,7 +1584,11 @@ void PhysicsServerExample::renderScene()
|
||||
|
||||
if (m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->isVRCamera())
|
||||
{
|
||||
gEnableRealTimeSimVR = true;
|
||||
if (!gEnableRealTimeSimVR)
|
||||
{
|
||||
gEnableRealTimeSimVR = true;
|
||||
m_physicsServer.enableRealTimeSimulation(1);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -1819,8 +1823,6 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt
|
||||
void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[4], float orn[4], float analogAxis)
|
||||
{
|
||||
|
||||
gEnableRealTimeSimVR = true;
|
||||
|
||||
if (controllerId <= 0 || controllerId >= MAX_VR_CONTROLLERS)
|
||||
{
|
||||
printf("Controller Id exceeds max: %d > %d", controllerId, MAX_VR_CONTROLLERS);
|
||||
|
||||
@@ -241,6 +241,12 @@ void PhysicsServerSharedMemory::stepSimulationRealTime(double dtInSec)
|
||||
m_data->m_commandProcessor->stepSimulationRealTime(dtInSec);
|
||||
}
|
||||
|
||||
void PhysicsServerSharedMemory::enableRealTimeSimulation(bool enableRealTimeSim)
|
||||
{
|
||||
m_data->m_commandProcessor->enableRealTimeSimulation(enableRealTimeSim);
|
||||
}
|
||||
|
||||
|
||||
|
||||
void PhysicsServerSharedMemory::processClientCommands()
|
||||
{
|
||||
|
||||
@@ -28,6 +28,8 @@ public:
|
||||
|
||||
virtual void stepSimulationRealTime(double dtInSec);
|
||||
|
||||
virtual void enableRealTimeSimulation(bool enableRealTimeSim);
|
||||
|
||||
//bool supportsJointMotor(class btMultiBody* body, int linkIndex);
|
||||
|
||||
|
||||
|
||||
Reference in New Issue
Block a user