also report VR events for HMD and generic tracked devices. Also expose those VR events to pybullet: expose a deviceTypeFilter, that defaults to VR_DEVICE_CONTROLLER

This commit is contained in:
Erwin Coumans
2017-04-07 22:53:36 -07:00
parent 82b576a390
commit 440d445a02
9 changed files with 197 additions and 31 deletions

View File

@@ -49,6 +49,8 @@ public:
virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4], float analogAxis) {} virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4], float analogAxis) {}
virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orientation[4]){} virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orientation[4]){}
virtual void vrHMDMoveCallback(int controllerId, float pos[4], float orientation[4]){}
virtual void vrGenericTrackerMoveCallback(int controllerId, float pos[4], float orientation[4]){}
virtual void processCommandLineArgs(int argc, char* argv[]){}; virtual void processCommandLineArgs(int argc, char* argv[]){};
}; };

View File

@@ -2537,11 +2537,20 @@ b3SharedMemoryCommandHandle b3RequestVREventsCommandInit(b3PhysicsClientHandle p
b3Assert(command); b3Assert(command);
command->m_type = CMD_REQUEST_VR_EVENTS_DATA; command->m_type = CMD_REQUEST_VR_EVENTS_DATA;
command->m_updateFlags = 0; command->m_updateFlags = VR_DEVICE_CONTROLLER;
return (b3SharedMemoryCommandHandle)command; return (b3SharedMemoryCommandHandle)command;
} }
void b3VREventsSetDeviceTypeFilter(b3SharedMemoryCommandHandle commandHandle, int deviceTypeFilter)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
if (command->m_type == CMD_REQUEST_VR_EVENTS_DATA)
{
command->m_updateFlags = deviceTypeFilter;
}
}
void b3GetVREventsData(b3PhysicsClientHandle physClient, struct b3VREventsData* vrEventsData) void b3GetVREventsData(b3PhysicsClientHandle physClient, struct b3VREventsData* vrEventsData)
{ {
PhysicsClient* cl = (PhysicsClient* ) physClient; PhysicsClient* cl = (PhysicsClient* ) physClient;

View File

@@ -352,6 +352,8 @@ int b3LoadBunnySetCollisionMargin(b3SharedMemoryCommandHandle commandHandle, dou
b3SharedMemoryCommandHandle b3RequestVREventsCommandInit(b3PhysicsClientHandle physClient); b3SharedMemoryCommandHandle b3RequestVREventsCommandInit(b3PhysicsClientHandle physClient);
void b3VREventsSetDeviceTypeFilter(b3SharedMemoryCommandHandle commandHandle, int deviceTypeFilter);
void b3GetVREventsData(b3PhysicsClientHandle physClient, struct b3VREventsData* vrEventsData); void b3GetVREventsData(b3PhysicsClientHandle physClient, struct b3VREventsData* vrEventsData);
b3SharedMemoryCommandHandle b3SetVRCameraStateCommandInit(b3PhysicsClientHandle physClient); b3SharedMemoryCommandHandle b3SetVRCameraStateCommandInit(b3PhysicsClientHandle physClient);

View File

@@ -605,6 +605,7 @@ struct b3VRControllerEvents
{ {
for (int i=0;i<MAX_VR_CONTROLLERS;i++) for (int i=0;i<MAX_VR_CONTROLLERS;i++)
{ {
m_vrEvents[i].m_deviceType = 0;
m_vrEvents[i].m_numButtonEvents = 0; m_vrEvents[i].m_numButtonEvents = 0;
m_vrEvents[i].m_numMoveEvents = 0; m_vrEvents[i].m_numMoveEvents = 0;
for (int b=0;b<MAX_VR_BUTTONS;b++) for (int b=0;b<MAX_VR_BUTTONS;b++)
@@ -628,6 +629,7 @@ struct b3VRControllerEvents
if (vrEvents[i].m_numMoveEvents+vrEvents[i].m_numButtonEvents) if (vrEvents[i].m_numMoveEvents+vrEvents[i].m_numButtonEvents)
{ {
m_vrEvents[controlledId].m_controllerId = vrEvents[i].m_controllerId; m_vrEvents[controlledId].m_controllerId = vrEvents[i].m_controllerId;
m_vrEvents[controlledId].m_deviceType = vrEvents[i].m_deviceType;
m_vrEvents[controlledId].m_pos[0] = vrEvents[i].m_pos[0]; m_vrEvents[controlledId].m_pos[0] = vrEvents[i].m_pos[0];
m_vrEvents[controlledId].m_pos[1] = vrEvents[i].m_pos[1]; m_vrEvents[controlledId].m_pos[1] = vrEvents[i].m_pos[1];
@@ -1209,7 +1211,9 @@ struct PhysicsServerCommandProcessorInternalData
bool m_allowRealTimeSimulation; bool m_allowRealTimeSimulation;
bool m_hasGround; bool m_hasGround;
b3VRControllerEvents m_vrEvents1; b3VRControllerEvents m_vrControllerEvents;
btAlignedObjectArray<b3KeyboardEvent> m_keyboardEvents; btAlignedObjectArray<b3KeyboardEvent> m_keyboardEvents;
btMultiBodyFixedConstraint* m_gripperRigidbodyFixed; btMultiBodyFixedConstraint* m_gripperRigidbodyFixed;
@@ -1324,7 +1328,7 @@ struct PhysicsServerCommandProcessorInternalData
m_pickedConstraint(0), m_pickedConstraint(0),
m_pickingMultiBodyPoint2Point(0) m_pickingMultiBodyPoint2Point(0)
{ {
m_vrEvents1.init(); m_vrControllerEvents.init();
initHandles(); initHandles();
#if 0 #if 0
@@ -2362,20 +2366,23 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
case CMD_REQUEST_VR_EVENTS_DATA: case CMD_REQUEST_VR_EVENTS_DATA:
{ {
BT_PROFILE("CMD_REQUEST_VR_EVENTS_DATA"); BT_PROFILE("CMD_REQUEST_VR_EVENTS_DATA");
serverStatusOut.m_sendVREvents.m_numVRControllerEvents = 0; serverStatusOut.m_sendVREvents.m_numVRControllerEvents = 0;
for (int i=0;i<MAX_VR_CONTROLLERS;i++) for (int i=0;i<MAX_VR_CONTROLLERS;i++)
{ {
b3VRControllerEvent& event = m_data->m_vrEvents1.m_vrEvents[i]; b3VRControllerEvent& event = m_data->m_vrControllerEvents.m_vrEvents[i];
if (event.m_numButtonEvents + event.m_numMoveEvents) if (clientCmd.m_updateFlags&event.m_deviceType)
{ {
serverStatusOut.m_sendVREvents.m_controllerEvents[serverStatusOut.m_sendVREvents.m_numVRControllerEvents++] = event; if (event.m_numButtonEvents + event.m_numMoveEvents)
event.m_numButtonEvents = 0;
event.m_numMoveEvents = 0;
for (int b=0;b<MAX_VR_BUTTONS;b++)
{ {
event.m_buttons[b] = 0; serverStatusOut.m_sendVREvents.m_controllerEvents[serverStatusOut.m_sendVREvents.m_numVRControllerEvents++] = event;
event.m_numButtonEvents = 0;
event.m_numMoveEvents = 0;
for (int b=0;b<MAX_VR_BUTTONS;b++)
{
event.m_buttons[b] = 0;
}
} }
} }
} }
@@ -5668,15 +5675,15 @@ void PhysicsServerCommandProcessor::enableRealTimeSimulation(bool enableRealTime
m_data->m_allowRealTimeSimulation = enableRealTimeSim; m_data->m_allowRealTimeSimulation = enableRealTimeSim;
} }
void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec, const struct b3VRControllerEvent* vrEvents, int numVREvents,const struct b3KeyboardEvent* keyEvents, int numKeyEvents) void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec, const struct b3VRControllerEvent* vrControllerEvents, int numVRControllerEvents,const struct b3KeyboardEvent* keyEvents, int numKeyEvents)
{ {
m_data->m_vrEvents1.addNewVREvents(vrEvents,numVREvents); m_data->m_vrControllerEvents.addNewVREvents(vrControllerEvents,numVRControllerEvents);
for (int i=0;i<m_data->m_stateLoggers.size();i++) for (int i=0;i<m_data->m_stateLoggers.size();i++)
{ {
if (m_data->m_stateLoggers[i]->m_loggingType==STATE_LOGGING_VR_CONTROLLERS) if (m_data->m_stateLoggers[i]->m_loggingType==STATE_LOGGING_VR_CONTROLLERS)
{ {
VRControllerStateLogger* vrLogger = (VRControllerStateLogger*) m_data->m_stateLoggers[i]; VRControllerStateLogger* vrLogger = (VRControllerStateLogger*) m_data->m_stateLoggers[i];
vrLogger->m_vrEvents.addNewVREvents(vrEvents,numVREvents); vrLogger->m_vrEvents.addNewVREvents(vrControllerEvents,numVRControllerEvents);
} }
} }

View File

@@ -1046,7 +1046,9 @@ public:
virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orientation[4]); virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orientation[4]);
virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4], float analogAxis); virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4], float analogAxis);
virtual void vrHMDMoveCallback(int controllerId, float pos[4], float orientation[4]);
virtual void vrGenericTrackerMoveCallback(int controllerId, float pos[4], float orientation[4]);
virtual bool mouseMoveCallback(float x,float y) virtual bool mouseMoveCallback(float x,float y)
{ {
@@ -2229,6 +2231,7 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt
m_args[0].m_csGUI->lock(); m_args[0].m_csGUI->lock();
m_args[0].m_vrControllerEvents[controllerId].m_controllerId = controllerId; m_args[0].m_vrControllerEvents[controllerId].m_controllerId = controllerId;
m_args[0].m_vrControllerEvents[controllerId].m_deviceType = VR_DEVICE_CONTROLLER;
m_args[0].m_vrControllerEvents[controllerId].m_pos[0] = trTotal.getOrigin()[0]; m_args[0].m_vrControllerEvents[controllerId].m_pos[0] = trTotal.getOrigin()[0];
m_args[0].m_vrControllerEvents[controllerId].m_pos[1] = trTotal.getOrigin()[1]; m_args[0].m_vrControllerEvents[controllerId].m_pos[1] = trTotal.getOrigin()[1];
m_args[0].m_vrControllerEvents[controllerId].m_pos[2] = trTotal.getOrigin()[2]; m_args[0].m_vrControllerEvents[controllerId].m_pos[2] = trTotal.getOrigin()[2];
@@ -2252,7 +2255,7 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt
void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[4], float orn[4], float analogAxis) void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[4], float orn[4], float analogAxis)
{ {
if (controllerId <= 0 || controllerId >= MAX_VR_CONTROLLERS) if (controllerId < 0 || controllerId >= MAX_VR_CONTROLLERS)
{ {
printf("Controller Id exceeds max: %d > %d", controllerId, MAX_VR_CONTROLLERS); printf("Controller Id exceeds max: %d > %d", controllerId, MAX_VR_CONTROLLERS);
return; return;
@@ -2299,6 +2302,7 @@ void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[
m_args[0].m_csGUI->lock(); m_args[0].m_csGUI->lock();
m_args[0].m_vrControllerEvents[controllerId].m_controllerId = controllerId; m_args[0].m_vrControllerEvents[controllerId].m_controllerId = controllerId;
m_args[0].m_vrControllerEvents[controllerId].m_deviceType = VR_DEVICE_CONTROLLER;
m_args[0].m_vrControllerEvents[controllerId].m_pos[0] = trTotal.getOrigin()[0]; m_args[0].m_vrControllerEvents[controllerId].m_pos[0] = trTotal.getOrigin()[0];
m_args[0].m_vrControllerEvents[controllerId].m_pos[1] = trTotal.getOrigin()[1]; m_args[0].m_vrControllerEvents[controllerId].m_pos[1] = trTotal.getOrigin()[1];
m_args[0].m_vrControllerEvents[controllerId].m_pos[2] = trTotal.getOrigin()[2]; m_args[0].m_vrControllerEvents[controllerId].m_pos[2] = trTotal.getOrigin()[2];
@@ -2311,4 +2315,87 @@ void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[
m_args[0].m_csGUI->unlock(); m_args[0].m_csGUI->unlock();
} }
void PhysicsServerExample::vrHMDMoveCallback(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;
}
//we may need to add some trLocal transform, to align the camera to our preferences
btTransform trLocal;
trLocal.setIdentity();
// trLocal.setRotation(btQuaternion(btVector3(0, 0, 1), SIMD_HALF_PI)*btQuaternion(btVector3(0, 1, 0), SIMD_HALF_PI));
btTransform trOrg;
trOrg.setIdentity();
trOrg.setOrigin(btVector3(pos[0], pos[1], pos[2]));
trOrg.setRotation(btQuaternion(orn[0], orn[1], orn[2], orn[3]));
btTransform tr2a;
tr2a.setIdentity();
btTransform tr2;
tr2.setIdentity();
tr2.setOrigin(gVRTeleportPos1);
tr2a.setRotation(gVRTeleportOrn);
btTransform trTotal = tr2*tr2a*trOrg*trLocal;
m_args[0].m_csGUI->lock();
m_args[0].m_vrControllerEvents[controllerId].m_controllerId = controllerId;
m_args[0].m_vrControllerEvents[controllerId].m_deviceType = VR_DEVICE_HMD;
m_args[0].m_vrControllerEvents[controllerId].m_pos[0] = trTotal.getOrigin()[0];
m_args[0].m_vrControllerEvents[controllerId].m_pos[1] = trTotal.getOrigin()[1];
m_args[0].m_vrControllerEvents[controllerId].m_pos[2] = trTotal.getOrigin()[2];
m_args[0].m_vrControllerEvents[controllerId].m_orn[0] = trTotal.getRotation()[0];
m_args[0].m_vrControllerEvents[controllerId].m_orn[1] = trTotal.getRotation()[1];
m_args[0].m_vrControllerEvents[controllerId].m_orn[2] = trTotal.getRotation()[2];
m_args[0].m_vrControllerEvents[controllerId].m_orn[3] = trTotal.getRotation()[3];
m_args[0].m_vrControllerEvents[controllerId].m_numMoveEvents++;
m_args[0].m_csGUI->unlock();
}
void PhysicsServerExample::vrGenericTrackerMoveCallback(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;
}
//we may need to add some trLocal transform, to align the camera to our preferences
btTransform trLocal;
trLocal.setIdentity();
trLocal.setRotation(btQuaternion(btVector3(0, 0, 1), SIMD_HALF_PI)*btQuaternion(btVector3(0, 1, 0), SIMD_HALF_PI));
btTransform trOrg;
trOrg.setIdentity();
trOrg.setOrigin(btVector3(pos[0], pos[1], pos[2]));
trOrg.setRotation(btQuaternion(orn[0], orn[1], orn[2], orn[3]));
btTransform tr2a;
tr2a.setIdentity();
btTransform tr2;
tr2.setIdentity();
tr2.setOrigin(gVRTeleportPos1);
tr2a.setRotation(gVRTeleportOrn);
btTransform trTotal = tr2*tr2a*trOrg*trLocal;
m_args[0].m_csGUI->lock();
m_args[0].m_vrControllerEvents[controllerId].m_controllerId = controllerId;
m_args[0].m_vrControllerEvents[controllerId].m_deviceType = VR_DEVICE_GENERIC_TRACKER;
m_args[0].m_vrControllerEvents[controllerId].m_pos[0] = trTotal.getOrigin()[0];
m_args[0].m_vrControllerEvents[controllerId].m_pos[1] = trTotal.getOrigin()[1];
m_args[0].m_vrControllerEvents[controllerId].m_pos[2] = trTotal.getOrigin()[2];
m_args[0].m_vrControllerEvents[controllerId].m_orn[0] = trTotal.getRotation()[0];
m_args[0].m_vrControllerEvents[controllerId].m_orn[1] = trTotal.getRotation()[1];
m_args[0].m_vrControllerEvents[controllerId].m_orn[2] = trTotal.getRotation()[2];
m_args[0].m_vrControllerEvents[controllerId].m_orn[3] = trTotal.getRotation()[3];
m_args[0].m_vrControllerEvents[controllerId].m_numMoveEvents++;
m_args[0].m_csGUI->unlock();
}
B3_STANDALONE_EXAMPLE(PhysicsServerCreateFunc) B3_STANDALONE_EXAMPLE(PhysicsServerCreateFunc)

View File

@@ -605,6 +605,7 @@ struct UserDebugDrawResultArgs
double m_parameterValue; double m_parameterValue;
}; };
struct SendVREvents struct SendVREvents
{ {
int m_numVRControllerEvents; int m_numVRControllerEvents;

View File

@@ -252,7 +252,9 @@ struct b3CameraImageData
enum b3VREventType enum b3VREventType
{ {
VR_CONTROLLER_MOVE_EVENT=1, VR_CONTROLLER_MOVE_EVENT=1,
VR_CONTROLLER_BUTTON_EVENT VR_CONTROLLER_BUTTON_EVENT=2,
VR_HMD_MOVE_EVENT=4,
VR_GENERIC_TRACKER_MOVE_EVENT=8,
}; };
#define MAX_VR_BUTTONS 64 #define MAX_VR_BUTTONS 64
@@ -271,9 +273,19 @@ enum b3VRButtonInfo
eButtonReleased = 4, eButtonReleased = 4,
}; };
enum eVRDeviceTypeEnums
{
VR_DEVICE_CONTROLLER=1,
VR_DEVICE_HMD=2,
VR_DEVICE_GENERIC_TRACKER=3,
};
struct b3VRControllerEvent struct b3VRControllerEvent
{ {
int m_controllerId;//valid for VR_CONTROLLER_MOVE_EVENT and VR_CONTROLLER_BUTTON_EVENT int m_controllerId;//valid for VR_CONTROLLER_MOVE_EVENT and VR_CONTROLLER_BUTTON_EVENT
int m_deviceType;
int m_numMoveEvents; int m_numMoveEvents;
int m_numButtonEvents; int m_numButtonEvents;
@@ -289,6 +301,11 @@ struct b3VREventsData
{ {
int m_numControllerEvents; int m_numControllerEvents;
struct b3VRControllerEvent* m_controllerEvents; struct b3VRControllerEvent* m_controllerEvents;
int m_numHmdEvents;
struct b3VRMoveEvent* m_hmdEvents;
int m_numGenericTrackerEvents;
struct b3VRMoveEvent* m_genericTrackerEvents;
}; };

View File

@@ -709,8 +709,50 @@ bool CMainApplication::HandleInput()
vr::VRControllerState_t state; vr::VRControllerState_t state;
if( m_pHMD->GetControllerState( unDevice, &state ,sizeof(vr::VRControllerState_t)) ) if( m_pHMD->GetControllerState( unDevice, &state ,sizeof(vr::VRControllerState_t)) )
{ {
b3Transform tr;
getControllerTransform(unDevice, tr);
float pos[3] = { tr.getOrigin()[0], tr.getOrigin()[1], tr.getOrigin()[2] };
b3Quaternion born = tr.getRotation();
float orn[4] = { born[0], born[1], born[2], born[3] };
//we need to have the 'move' events, so no early out here //we need to have the 'move' events, so no early out here
//if (sPrevStates[unDevice].unPacketNum != state.unPacketNum) //if (sPrevStates[unDevice].unPacketNum != state.unPacketNum)
if( m_pHMD->GetTrackedDeviceClass( unDevice) == vr::TrackedDeviceClass_HMD )
{
Matrix4 rotYtoZ = rotYtoZ.identity();
//some Bullet apps (especially robotics related) require Z as up-axis)
if (m_app->getUpAxis()==2)
{
rotYtoZ.rotateX(-90);
}
Matrix4 viewMatCenter = m_mat4HMDPose * rotYtoZ;
const float* mat = viewMatCenter.invertAffine().get();
pos[0] = mat[12];
pos[1] = mat[13];
pos[2] = mat[14];
b3Matrix3x3 bmat;
for (int i=0;i<3;i++)
{
for (int j=0;j<3;j++)
{
bmat[i][j] = mat[i+4*j];
}
}
b3Quaternion orn2;
bmat.getRotation(orn2);
orn[0] = orn2[0];
orn[1] = orn2[1];
orn[2] = orn2[2];
orn[3] = orn2[3];
sExample->vrHMDMoveCallback(unDevice, pos,orn);
}
if( m_pHMD->GetTrackedDeviceClass( unDevice) == vr::TrackedDeviceClass_GenericTracker )
{
sExample->vrGenericTrackerMoveCallback(unDevice, pos,orn);
}
if( m_pHMD->GetTrackedDeviceClass( unDevice) == vr::TrackedDeviceClass_Controller ) if( m_pHMD->GetTrackedDeviceClass( unDevice) == vr::TrackedDeviceClass_Controller )
{ {
sPrevStates[unDevice].unPacketNum = state.unPacketNum; sPrevStates[unDevice].unPacketNum = state.unPacketNum;
@@ -723,11 +765,6 @@ bool CMainApplication::HandleInput()
if (isTrigger) if (isTrigger)
{ {
b3Transform tr;
getControllerTransform(unDevice, tr);
float pos[3] = { tr.getOrigin()[0], tr.getOrigin()[1], tr.getOrigin()[2] };
b3Quaternion born = tr.getRotation();
float orn[4] = { born[0], born[1], born[2], born[3] };
//pressed now, not pressed before -> raise a button down event //pressed now, not pressed before -> raise a button down event
if ((sPrevStates[unDevice].ulButtonPressed&trigger)==0) if ((sPrevStates[unDevice].ulButtonPressed&trigger)==0)
@@ -765,11 +802,6 @@ bool CMainApplication::HandleInput()
{ {
b3Transform tr;
getControllerTransform(unDevice, tr);
float pos[3] = { tr.getOrigin()[0], tr.getOrigin()[1], tr.getOrigin()[2] };
b3Quaternion born = tr.getRotation();
float orn[4] = { born[0], born[1], born[2], born[3] };
// printf("Device RELEASED: %d, button %d\n", unDevice,button); // printf("Device RELEASED: %d, button %d\n", unDevice,button);
//not pressed now, but pressed before -> raise a button up event //not pressed now, but pressed before -> raise a button up event

View File

@@ -3166,10 +3166,11 @@ static PyObject* pybullet_getVREvents(PyObject* self, PyObject* args, PyObject*
b3SharedMemoryCommandHandle commandHandle; b3SharedMemoryCommandHandle commandHandle;
b3SharedMemoryStatusHandle statusHandle; b3SharedMemoryStatusHandle statusHandle;
int statusType; int statusType;
int deviceTypeFilter = VR_DEVICE_CONTROLLER;
int physicsClientId = 0; int physicsClientId = 0;
b3PhysicsClientHandle sm = 0; b3PhysicsClientHandle sm = 0;
static char* kwlist[] = {"physicsClientId", NULL}; static char* kwlist[] = {"deviceTypeFilter", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|i", kwlist, &physicsClientId)) if (!PyArg_ParseTupleAndKeywords(args, keywds, "|ii", kwlist, &deviceTypeFilter, &physicsClientId))
{ {
return NULL; return NULL;
} }
@@ -3182,6 +3183,9 @@ static PyObject* pybullet_getVREvents(PyObject* self, PyObject* args, PyObject*
} }
commandHandle = b3RequestVREventsCommandInit(sm); commandHandle = b3RequestVREventsCommandInit(sm);
b3VREventsSetDeviceTypeFilter(commandHandle, deviceTypeFilter);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
statusType = b3GetStatusType(statusHandle); statusType = b3GetStatusType(statusHandle);
if (statusType == CMD_REQUEST_VR_EVENTS_DATA_COMPLETED) if (statusType == CMD_REQUEST_VR_EVENTS_DATA_COMPLETED)
@@ -3194,7 +3198,7 @@ static PyObject* pybullet_getVREvents(PyObject* self, PyObject* args, PyObject*
vrEventsObj = PyTuple_New(vrEvents.m_numControllerEvents); vrEventsObj = PyTuple_New(vrEvents.m_numControllerEvents);
for (i = 0; i < vrEvents.m_numControllerEvents; i++) for (i = 0; i < vrEvents.m_numControllerEvents; i++)
{ {
PyObject* vrEventObj = PyTuple_New(7); PyObject* vrEventObj = PyTuple_New(8);
PyTuple_SetItem(vrEventObj, 0, PyInt_FromLong(vrEvents.m_controllerEvents[i].m_controllerId)); PyTuple_SetItem(vrEventObj, 0, PyInt_FromLong(vrEvents.m_controllerEvents[i].m_controllerId));
{ {
@@ -3226,6 +3230,7 @@ static PyObject* pybullet_getVREvents(PyObject* self, PyObject* args, PyObject*
} }
PyTuple_SetItem(vrEventObj, 6, buttonsObj); PyTuple_SetItem(vrEventObj, 6, buttonsObj);
} }
PyTuple_SetItem(vrEventObj, 7, PyInt_FromLong(vrEvents.m_controllerEvents[i].m_deviceType));
PyTuple_SetItem(vrEventsObj, i, vrEventObj); PyTuple_SetItem(vrEventsObj, i, vrEventObj);
} }
return vrEventsObj; return vrEventsObj;
@@ -5592,6 +5597,10 @@ initpybullet(void)
PyModule_AddIntConstant(m, "VR_MAX_CONTROLLERS", MAX_VR_CONTROLLERS); PyModule_AddIntConstant(m, "VR_MAX_CONTROLLERS", MAX_VR_CONTROLLERS);
PyModule_AddIntConstant(m, "VR_MAX_BUTTONS", MAX_VR_BUTTONS); PyModule_AddIntConstant(m, "VR_MAX_BUTTONS", MAX_VR_BUTTONS);
PyModule_AddIntConstant(m, "VR_DEVICE_CONTROLLER", VR_DEVICE_CONTROLLER);
PyModule_AddIntConstant(m, "VR_DEVICE_HMD", VR_DEVICE_HMD);
PyModule_AddIntConstant(m, "VR_DEVICE_GENERIC_TRACKER", VR_DEVICE_GENERIC_TRACKER);
PyModule_AddIntConstant(m, "KEY_IS_DOWN", eButtonIsDown); PyModule_AddIntConstant(m, "KEY_IS_DOWN", eButtonIsDown);
PyModule_AddIntConstant(m, "KEY_WAS_TRIGGERED", eButtonTriggered); PyModule_AddIntConstant(m, "KEY_WAS_TRIGGERED", eButtonTriggered);
PyModule_AddIntConstant(m, "KEY_WAS_RELEASED", eButtonReleased); PyModule_AddIntConstant(m, "KEY_WAS_RELEASED", eButtonReleased);