fix issues with VR physics server
This commit is contained in:
@@ -556,6 +556,9 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
|
|||||||
|
|
||||||
m_data->m_dynamicsWorld = new btMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration);
|
m_data->m_dynamicsWorld = new btMultiBodyDynamicsWorld(m_data->m_dispatcher, m_data->m_broadphase, m_data->m_solver, m_data->m_collisionConfiguration);
|
||||||
|
|
||||||
|
//Workaround: in a VR application, where we avoid synchronizaing between GFX/Physics threads, we don't want to resize this array, so pre-allocate it
|
||||||
|
m_data->m_dynamicsWorld->getCollisionObjectArray().reserve(8192);
|
||||||
|
|
||||||
m_data->m_remoteDebugDrawer = new SharedMemoryDebugDrawer();
|
m_data->m_remoteDebugDrawer = new SharedMemoryDebugDrawer();
|
||||||
|
|
||||||
|
|
||||||
@@ -2694,13 +2697,16 @@ void PhysicsServerCommandProcessor::replayFromLogFile(const char* fileName)
|
|||||||
|
|
||||||
btVector3 gVRGripperPos(0,0,0);
|
btVector3 gVRGripperPos(0,0,0);
|
||||||
btQuaternion gVRGripperOrn(0,0,0,1);
|
btQuaternion gVRGripperOrn(0,0,0,1);
|
||||||
|
int gDroppedSimulationSteps = 0;
|
||||||
|
int gNumSteps = 0;
|
||||||
|
double gDtInSec = 0.f;
|
||||||
|
double gSubStep = 0.f;
|
||||||
void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
|
void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
|
||||||
{
|
{
|
||||||
if (m_data->m_allowRealTimeSimulation && m_data->m_guiHelper)
|
if (m_data->m_allowRealTimeSimulation && m_data->m_guiHelper)
|
||||||
{
|
{
|
||||||
btAlignedObjectArray<char> bufferServerToClient;
|
static btAlignedObjectArray<char> gBufferServerToClient;
|
||||||
bufferServerToClient.resize(32768);
|
gBufferServerToClient.resize(32768);
|
||||||
|
|
||||||
|
|
||||||
if (!m_data->m_hasGround)
|
if (!m_data->m_hasGround)
|
||||||
@@ -2710,14 +2716,14 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
|
|||||||
int bodyId = 0;
|
int bodyId = 0;
|
||||||
|
|
||||||
|
|
||||||
loadUrdf("plane.urdf", btVector3(0, 0, 0), btQuaternion(0, 0, 0, 1), true, true, &bodyId, &bufferServerToClient[0], bufferServerToClient.size());
|
loadUrdf("plane.urdf", btVector3(0, 0, 0), btQuaternion(0, 0, 0, 1), true, true, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||||
}
|
}
|
||||||
|
|
||||||
if (0)//m_data->m_gripperRigidbodyFixed==0)
|
if (0)//m_data->m_gripperRigidbodyFixed==0)
|
||||||
{
|
{
|
||||||
int bodyId = 0;
|
int bodyId = 0;
|
||||||
|
|
||||||
loadUrdf("pr2_gripper.urdf",btVector3(0, 0, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &bufferServerToClient[0], bufferServerToClient.size());
|
loadUrdf("pr2_gripper.urdf",btVector3(0, 0, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||||
|
|
||||||
InteralBodyData* parentBody = m_data->getHandle(bodyId);
|
InteralBodyData* parentBody = m_data->getHandle(bodyId);
|
||||||
if (parentBody->m_multiBody)
|
if (parentBody->m_multiBody)
|
||||||
@@ -2747,13 +2753,13 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
|
|||||||
int maxSteps = 3;
|
int maxSteps = 3;
|
||||||
|
|
||||||
int numSteps = m_data->m_dynamicsWorld->stepSimulation(dtInSec,maxSteps,m_data->m_physicsDeltaTime);
|
int numSteps = m_data->m_dynamicsWorld->stepSimulation(dtInSec,maxSteps,m_data->m_physicsDeltaTime);
|
||||||
int droppedSteps = numSteps > maxSteps ? numSteps - maxSteps : 0;
|
gDroppedSimulationSteps += numSteps > maxSteps ? numSteps - maxSteps : 0;
|
||||||
static int skipReport = 0;
|
|
||||||
skipReport++;
|
if (numSteps)
|
||||||
if (skipReport>100)
|
|
||||||
{
|
{
|
||||||
skipReport = 0;
|
gNumSteps = numSteps;
|
||||||
//printf("numSteps: %d (dropped %d), %f (internal step = %f)\n", numSteps, droppedSteps , dtInSec, m_data->m_physicsDeltaTime);
|
gDtInSec = dtInSec;
|
||||||
|
gSubStep = m_data->m_physicsDeltaTime;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -13,7 +13,8 @@
|
|||||||
#include "../Utils/b3Clock.h"
|
#include "../Utils/b3Clock.h"
|
||||||
#include "../MultiThreading/b3ThreadSupportInterface.h"
|
#include "../MultiThreading/b3ThreadSupportInterface.h"
|
||||||
|
|
||||||
#define MAX_VR_CONTROLLERS 4
|
#define MAX_VR_CONTROLLERS 8
|
||||||
|
|
||||||
|
|
||||||
extern btVector3 gLastPickPos;
|
extern btVector3 gLastPickPos;
|
||||||
btVector3 gVRTeleportPos(0,0,0);
|
btVector3 gVRTeleportPos(0,0,0);
|
||||||
@@ -880,6 +881,12 @@ static float vrOffset[16]={1,0,0,0,
|
|||||||
0,0,0,0};
|
0,0,0,0};
|
||||||
|
|
||||||
|
|
||||||
|
extern int gDroppedSimulationSteps;
|
||||||
|
extern int gNumSteps;
|
||||||
|
extern double gDtInSec;
|
||||||
|
extern double gSubStep;
|
||||||
|
|
||||||
|
|
||||||
void PhysicsServerExample::renderScene()
|
void PhysicsServerExample::renderScene()
|
||||||
{
|
{
|
||||||
///debug rendering
|
///debug rendering
|
||||||
@@ -925,24 +932,38 @@ void PhysicsServerExample::renderScene()
|
|||||||
//some little experiment to add text/HUD to a VR camera (HTC Vive/Oculus Rift)
|
//some little experiment to add text/HUD to a VR camera (HTC Vive/Oculus Rift)
|
||||||
|
|
||||||
static int frameCount=0;
|
static int frameCount=0;
|
||||||
frameCount++;
|
|
||||||
char bla[1024];
|
|
||||||
|
|
||||||
static btScalar prevTime = m_clock.getTimeSeconds();
|
static btScalar prevTime = m_clock.getTimeSeconds();
|
||||||
btScalar curTime = m_clock.getTimeSeconds();
|
frameCount++;
|
||||||
static btScalar deltaTime = 0.f;
|
static char line0[1024];
|
||||||
static int count = 10;
|
static char line1[1024];
|
||||||
if (count-- < 0)
|
|
||||||
{
|
static btScalar worseFps = 1000000;
|
||||||
count = 10;
|
int numFrames = 200;
|
||||||
deltaTime = curTime - prevTime;
|
static int count = 0;
|
||||||
}
|
count++;
|
||||||
if (deltaTime == 0)
|
|
||||||
deltaTime = 1000;
|
if (0 == (count & 1))
|
||||||
|
{
|
||||||
|
btScalar curTime = m_clock.getTimeSeconds();
|
||||||
|
btScalar fps = 1. / (curTime - prevTime);
|
||||||
|
prevTime = curTime;
|
||||||
|
if (fps < worseFps)
|
||||||
|
{
|
||||||
|
worseFps = fps;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (count > numFrames)
|
||||||
|
{
|
||||||
|
count = 0;
|
||||||
|
sprintf(line0, "Graphics FPS (worse) = %f, frame %d", worseFps, frameCount / 2);
|
||||||
|
|
||||||
|
sprintf(line1, "Physics Steps = %d, Dropped = %d, dt %f, Substep %f)", gNumSteps, gDroppedSimulationSteps, gDtInSec, gSubStep);
|
||||||
|
gDroppedSimulationSteps = 0;
|
||||||
|
|
||||||
|
worseFps = 1000000;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
prevTime = curTime;
|
|
||||||
|
|
||||||
sprintf(bla,"VR sub-title text test,fps = %f, frame %d", 1./deltaTime, frameCount/2);
|
|
||||||
float pos[4];
|
float pos[4];
|
||||||
m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->getCameraTargetPosition(pos);
|
m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->getCameraTargetPosition(pos);
|
||||||
pos[0]+=gVRTeleportPos[0];
|
pos[0]+=gVRTeleportPos[0];
|
||||||
@@ -965,12 +986,12 @@ void PhysicsServerExample::renderScene()
|
|||||||
float upMag = -.6;
|
float upMag = -.6;
|
||||||
btVector3 side = viewTrInv.getBasis().getColumn(0);
|
btVector3 side = viewTrInv.getBasis().getColumn(0);
|
||||||
btVector3 up = viewTrInv.getBasis().getColumn(1);
|
btVector3 up = viewTrInv.getBasis().getColumn(1);
|
||||||
up+=0.35*side;
|
up+=0.6*side;
|
||||||
m_guiHelper->getAppInterface()->drawText3D(bla,pos[0]+upMag*up[0],pos[1]+upMag*up[1],pos[2]+upMag*up[2],1);
|
m_guiHelper->getAppInterface()->drawText3D(line0,pos[0]+upMag*up[0],pos[1]+upMag*up[1],pos[2]+upMag*up[2],1);
|
||||||
//btVector3 fwd = viewTrInv.getBasis().getColumn(2);
|
//btVector3 fwd = viewTrInv.getBasis().getColumn(2);
|
||||||
sprintf(bla,"VR line 2 sub-title text test, frame %d", frameCount/2);
|
|
||||||
upMag = -0.7;
|
upMag = -0.7;
|
||||||
m_guiHelper->getAppInterface()->drawText3D(bla,pos[0]+upMag*up[0],pos[1]+upMag*up[1],pos[2]+upMag*up[2],1);
|
m_guiHelper->getAppInterface()->drawText3D(line1,pos[0]+upMag*up[0],pos[1]+upMag*up[1],pos[2]+upMag*up[2],1);
|
||||||
}
|
}
|
||||||
|
|
||||||
//m_args[0].m_cs->unlock();
|
//m_args[0].m_cs->unlock();
|
||||||
@@ -1083,7 +1104,7 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt
|
|||||||
{
|
{
|
||||||
//printf("controllerId %d, button=%d\n",controllerId, button);
|
//printf("controllerId %d, button=%d\n",controllerId, button);
|
||||||
|
|
||||||
if (controllerId<0 || controllerId>MAX_VR_CONTROLLERS)
|
if (controllerId<0 || controllerId>=MAX_VR_CONTROLLERS)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
if (button==1 && state==0)
|
if (button==1 && state==0)
|
||||||
@@ -1118,6 +1139,11 @@ extern btQuaternion gVRGripperOrn;
|
|||||||
void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[4], float orn[4])
|
void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[4], float orn[4])
|
||||||
{
|
{
|
||||||
|
|
||||||
|
if (controllerId <= 0 || controllerId >= MAX_VR_CONTROLLERS)
|
||||||
|
{
|
||||||
|
printf("Controller Id exceeds max: %d > %d", controllerId, MAX_VR_CONTROLLERS);
|
||||||
|
return;
|
||||||
|
}
|
||||||
m_args[0].m_vrControllerPos[controllerId].setValue(pos[0]+gVRTeleportPos[0],pos[1]+gVRTeleportPos[1],pos[2]+gVRTeleportPos[2]);
|
m_args[0].m_vrControllerPos[controllerId].setValue(pos[0]+gVRTeleportPos[0],pos[1]+gVRTeleportPos[1],pos[2]+gVRTeleportPos[2]);
|
||||||
m_args[0].m_vrControllerOrn[controllerId].setValue(orn[0],orn[1],orn[2],orn[3]);
|
m_args[0].m_vrControllerOrn[controllerId].setValue(orn[0],orn[1],orn[2],orn[3]);
|
||||||
|
|
||||||
|
|||||||
@@ -625,6 +625,9 @@ void CMainApplication::Shutdown()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
sExample->exitPhysics();
|
||||||
|
delete sExample;
|
||||||
|
|
||||||
delete m_app;
|
delete m_app;
|
||||||
m_app=0;
|
m_app=0;
|
||||||
|
|
||||||
@@ -752,13 +755,11 @@ bool CMainApplication::HandleInput()
|
|||||||
//-----------------------------------------------------------------------------
|
//-----------------------------------------------------------------------------
|
||||||
// Purpose:
|
// Purpose:
|
||||||
//-----------------------------------------------------------------------------
|
//-----------------------------------------------------------------------------
|
||||||
|
|
||||||
void CMainApplication::RunMainLoop()
|
void CMainApplication::RunMainLoop()
|
||||||
{
|
{
|
||||||
bool bQuit = false;
|
bool bQuit = false;
|
||||||
|
|
||||||
//SDL_StartTextInput();
|
|
||||||
//SDL_ShowCursor( SDL_DISABLE );
|
|
||||||
|
|
||||||
while ( !bQuit && !m_app->m_window->requestedExit())
|
while ( !bQuit && !m_app->m_window->requestedExit())
|
||||||
{
|
{
|
||||||
bQuit = HandleInput();
|
bQuit = HandleInput();
|
||||||
@@ -766,7 +767,6 @@ void CMainApplication::RunMainLoop()
|
|||||||
RenderFrame();
|
RenderFrame();
|
||||||
}
|
}
|
||||||
|
|
||||||
//SDL_StopTextInput();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user