OpenVR support: track multiple controllers and buttons

This commit is contained in:
erwin coumans
2016-07-18 23:13:46 -07:00
parent c28cd03fbd
commit 2302709e2d
2 changed files with 44 additions and 47 deletions

View File

@@ -140,10 +140,10 @@ void MotionThreadFunc(void* userPtr,void* lsMemory)
btVector3 from = args->m_pos; btVector3 from = args->m_pos;
btMatrix3x3 mat(args->m_orn); btMatrix3x3 mat(args->m_orn);
btScalar pickDistance = 100.;
btVector3 toX = args->m_pos+mat.getColumn(0); btVector3 toX = args->m_pos+mat.getColumn(0);
btVector3 toY = args->m_pos+mat.getColumn(1); btVector3 toY = args->m_pos+mat.getColumn(1);
btVector3 toZ = args->m_pos+mat.getColumn(2)*50.; btVector3 toZ = args->m_pos+mat.getColumn(2)*pickDistance;
if (args->m_isPicking) if (args->m_isPicking)

View File

@@ -30,11 +30,14 @@ int gSharedMemoryKey = -1;
#include "pathtools.h" #include "pathtools.h"
CommonExampleInterface* sExample; CommonExampleInterface* sExample;
int sIsPressed=-1;
int sPrevPacketNum=0; int sPrevPacketNum=0;
GUIHelperInterface* sGuiPtr = 0; GUIHelperInterface* sGuiPtr = 0;
static vr::VRControllerState_t sPrevStates[vr::k_unMaxTrackedDeviceCount] = { 0 };
#if defined(POSIX) #if defined(POSIX)
#include "unistd.h" #include "unistd.h"
#endif #endif
@@ -663,63 +666,57 @@ bool CMainApplication::HandleInput()
vr::VRControllerState_t state; vr::VRControllerState_t state;
if( m_pHMD->GetControllerState( unDevice, &state ) ) if( m_pHMD->GetControllerState( unDevice, &state ) )
{ {
uint64_t trigger = vr::ButtonMaskFromId(vr::k_EButton_SteamVR_Trigger); //we need to have the 'move' events, so no early out here
//if (sPrevStates[unDevice].unPacketNum != state.unPacketNum)
if (sPrevPacketNum != state.unPacketNum)
{ {
sPrevStates[unDevice].unPacketNum = state.unPacketNum;
for (int button = 0; button < vr::k_EButton_Max; button++)
{
uint64_t trigger = vr::ButtonMaskFromId((vr::EVRButtonId)button);
static int counter=0;
sPrevPacketNum = state.unPacketNum;
//b3Printf(".");
bool isTrigger = (state.ulButtonPressed&trigger) != 0; bool isTrigger = (state.ulButtonPressed&trigger) != 0;
if (isTrigger) if (isTrigger)
{ {
//printf("unDevice=%d\n",unDevice);
b3Transform tr; b3Transform tr;
getControllerTransform(unDevice, tr); getControllerTransform(unDevice, tr);
float pos[3] = { tr.getOrigin()[0], tr.getOrigin()[1], tr.getOrigin()[2] }; float pos[3] = { tr.getOrigin()[0], tr.getOrigin()[1], tr.getOrigin()[2] };
b3Quaternion born = tr.getRotation(); b3Quaternion born = tr.getRotation();
float orn[4] = { born[0], born[1], born[2], born[3] }; float orn[4] = { born[0], born[1], born[2], born[3] };
//pressed now, not pressed before -> raise a button down event
if (sIsPressed!=unDevice) if ((sPrevStates[unDevice].ulButtonPressed&trigger)==0)
{ {
b3Printf("trigger pressed %d, %d\n",counter++, unDevice); // printf("Device PRESSED: %d, button %d\n", unDevice, button);
sIsPressed=unDevice; sExample->vrControllerButtonCallback(unDevice, button, 1, pos, orn);
}
sExample->vrControllerButtonCallback(unDevice,1,1,pos, orn); else
//
//virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4]) {}
//virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orientation[4]){}
//sExample->start
} else
{ {
// printf("Device MOVED: %d\n", unDevice);
sExample->vrControllerMoveCallback(unDevice, pos, orn); sExample->vrControllerMoveCallback(unDevice, pos, orn);
} }
//sExample->exitPhysics(); }
//m_app->m_instancingRenderer->removeAllInstances(); else
///sExample->initPhysics();
} else
{ {
if (unDevice==sIsPressed) //not pressed now, but pressed before -> raise a button up event
if ((sPrevStates[unDevice].ulButtonPressed&trigger) != 0)
{ {
b3Transform tr; b3Transform tr;
getControllerTransform(unDevice, tr); getControllerTransform(unDevice, tr);
float pos[3] = { tr.getOrigin()[0], tr.getOrigin()[1], tr.getOrigin()[2] }; float pos[3] = { tr.getOrigin()[0], tr.getOrigin()[1], tr.getOrigin()[2] };
b3Quaternion born = tr.getRotation(); b3Quaternion born = tr.getRotation();
float orn[4] = { born[0], born[1], born[2], born[3] }; float orn[4] = { born[0], born[1], born[2], born[3] };
// printf("Device RELEASED: %d, button %d\n", unDevice,button);
sIsPressed=-1; sExample->vrControllerButtonCallback(unDevice, button, 0, pos, orn);
printf("device released: %d",unDevice); }
sExample->vrControllerButtonCallback(unDevice,1,0,pos, orn);
} }
} }
} }
m_rbShowTrackedDevice[ unDevice ] = state.ulButtonPressed == 0; m_rbShowTrackedDevice[ unDevice ] = state.ulButtonPressed == 0;
} }
sPrevStates[unDevice] = state;
} }
return bRet; return bRet;