fix signal handling in ExampleBrowser on linux/mac on termination
expose all analogue axes from OpenVR (5 controllers, each x,y -> 10 floats) in pybullet.getVREvents(allAnalogAxes=1)
This commit is contained in:
@@ -8,7 +8,9 @@ import pybullet as p
|
||||
CONTROLLER_ID = 0
|
||||
POSITION=1
|
||||
ORIENTATION=2
|
||||
NUM_MOVE_EVENTS=5
|
||||
BUTTONS=6
|
||||
ANALOG_AXIS=8
|
||||
|
||||
#assume that the VR physics server is already started before
|
||||
c = p.connect(p.SHARED_MEMORY)
|
||||
@@ -20,7 +22,7 @@ p.setInternalSimFlags(0)#don't load default robot assets etc
|
||||
p.resetSimulation()
|
||||
p.loadURDF("plane.urdf")
|
||||
|
||||
prevPosition=[None]*p.VR_MAX_CONTROLLERS
|
||||
prevPosition=[[0,0,0]]*p.VR_MAX_CONTROLLERS
|
||||
colors=[0.,0.5,0.5]*p.VR_MAX_CONTROLLERS
|
||||
widths = [3]*p.VR_MAX_CONTROLLERS
|
||||
|
||||
@@ -32,10 +34,27 @@ colors[3] = [0,0,0.5]
|
||||
colors[4] = [0.5,0.5,0.]
|
||||
colors[5] = [.5,.5,.5]
|
||||
|
||||
while True:
|
||||
controllerId = -1
|
||||
pt=[0,0,0]
|
||||
|
||||
print("waiting for VR controller trigger")
|
||||
while (controllerId<0):
|
||||
events = p.getVREvents()
|
||||
for e in (events):
|
||||
if (e[BUTTONS][33]==p.VR_BUTTON_IS_DOWN):
|
||||
controllerId = e[CONTROLLER_ID]
|
||||
if (e[BUTTONS][32]==p.VR_BUTTON_IS_DOWN):
|
||||
controllerId = e[CONTROLLER_ID]
|
||||
|
||||
print("Using controllerId="+str(controllerId))
|
||||
|
||||
while True:
|
||||
events = p.getVREvents(allAnalogAxes=1)
|
||||
|
||||
for e in (events):
|
||||
if (e[CONTROLLER_ID]==controllerId ):
|
||||
for a in range(10):
|
||||
print("analog axis"+str(a)+"="+str(e[8][a]))
|
||||
if (e[BUTTONS][33]&p.VR_BUTTON_WAS_TRIGGERED):
|
||||
prevPosition[e[CONTROLLER_ID]] = e[POSITION]
|
||||
if (e[BUTTONS][32]&p.VR_BUTTON_WAS_TRIGGERED):
|
||||
@@ -51,7 +70,10 @@ while True:
|
||||
pt = prevPosition[e[CONTROLLER_ID]]
|
||||
|
||||
#print(prevPosition[e[0]])
|
||||
#print(e[1])
|
||||
print("e[POSITION]")
|
||||
print(e[POSITION])
|
||||
print("pt")
|
||||
print(pt)
|
||||
diff = [pt[0]-e[POSITION][0],pt[1]-e[POSITION][1],pt[2]-e[POSITION][2]]
|
||||
lenSqr = diff[0]*diff[0]+diff[1]*diff[1]+diff[2]*diff[2]
|
||||
ptDistThreshold = 0.01
|
||||
|
||||
@@ -4277,9 +4277,10 @@ static PyObject* pybullet_getVREvents(PyObject* self, PyObject* args, PyObject*
|
||||
int statusType;
|
||||
int deviceTypeFilter = VR_DEVICE_CONTROLLER;
|
||||
int physicsClientId = 0;
|
||||
int allAnalogAxes = 0;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
static char* kwlist[] = {"deviceTypeFilter", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|ii", kwlist, &deviceTypeFilter, &physicsClientId))
|
||||
static char* kwlist[] = {"deviceTypeFilter", "allAnalogAxes", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|iii", kwlist, &deviceTypeFilter, &allAnalogAxes, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -4307,7 +4308,8 @@ static PyObject* pybullet_getVREvents(PyObject* self, PyObject* args, PyObject*
|
||||
vrEventsObj = PyTuple_New(vrEvents.m_numControllerEvents);
|
||||
for (i = 0; i < vrEvents.m_numControllerEvents; i++)
|
||||
{
|
||||
PyObject* vrEventObj = PyTuple_New(8);
|
||||
int numFields = allAnalogAxes? 9 : 8;
|
||||
PyObject* vrEventObj = PyTuple_New(numFields);
|
||||
|
||||
PyTuple_SetItem(vrEventObj, 0, PyInt_FromLong(vrEvents.m_controllerEvents[i].m_controllerId));
|
||||
{
|
||||
@@ -4340,6 +4342,19 @@ static PyObject* pybullet_getVREvents(PyObject* self, PyObject* args, PyObject*
|
||||
PyTuple_SetItem(vrEventObj, 6, buttonsObj);
|
||||
}
|
||||
PyTuple_SetItem(vrEventObj, 7, PyInt_FromLong(vrEvents.m_controllerEvents[i].m_deviceType));
|
||||
|
||||
if (allAnalogAxes)
|
||||
{
|
||||
PyObject* buttonsObj = PyTuple_New(MAX_VR_ANALOG_AXIS*2);
|
||||
int b;
|
||||
for (b = 0; b < MAX_VR_ANALOG_AXIS*2; b++)
|
||||
{
|
||||
PyObject* axisVal = PyFloat_FromDouble(vrEvents.m_controllerEvents[i].m_auxAnalogAxis[b]);
|
||||
PyTuple_SetItem(buttonsObj, b, axisVal);
|
||||
}
|
||||
PyTuple_SetItem(vrEventObj, 8, buttonsObj);
|
||||
}
|
||||
|
||||
PyTuple_SetItem(vrEventsObj, i, vrEventObj);
|
||||
}
|
||||
return vrEventsObj;
|
||||
|
||||
Reference in New Issue
Block a user