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:
@@ -889,8 +889,18 @@ struct b3VRControllerEvents
|
||||
if (vrEvents[i].m_numMoveEvents)
|
||||
{
|
||||
m_vrEvents[controlledId].m_analogAxis = vrEvents[i].m_analogAxis;
|
||||
for (int a=0;a<10;a++)
|
||||
{
|
||||
m_vrEvents[controlledId].m_auxAnalogAxis[a] = vrEvents[i].m_auxAnalogAxis[a];
|
||||
}
|
||||
} else
|
||||
{
|
||||
m_vrEvents[controlledId].m_analogAxis = 0;
|
||||
for (int a=0;a<10;a++)
|
||||
{
|
||||
m_vrEvents[controlledId].m_auxAnalogAxis[a] = 0;
|
||||
}
|
||||
}
|
||||
|
||||
if (vrEvents[i].m_numMoveEvents+vrEvents[i].m_numButtonEvents)
|
||||
{
|
||||
m_vrEvents[controlledId].m_controllerId = vrEvents[i].m_controllerId;
|
||||
|
||||
@@ -1330,7 +1330,7 @@ public:
|
||||
btVector3 getRayTo(int x,int y);
|
||||
|
||||
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, float auxAnalogAxes[10]);
|
||||
virtual void vrHMDMoveCallback(int controllerId, float pos[4], float orientation[4]);
|
||||
virtual void vrGenericTrackerMoveCallback(int controllerId, float pos[4], float orientation[4]);
|
||||
|
||||
@@ -2874,7 +2874,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, float auxAnalogAxes[10])
|
||||
{
|
||||
|
||||
if (controllerId < 0 || controllerId >= MAX_VR_CONTROLLERS)
|
||||
@@ -2927,6 +2927,11 @@ void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[
|
||||
m_args[0].m_vrControllerEvents[controllerId].m_orn[3] = trTotal.getRotation()[3];
|
||||
m_args[0].m_vrControllerEvents[controllerId].m_numMoveEvents++;
|
||||
m_args[0].m_vrControllerEvents[controllerId].m_analogAxis = analogAxis;
|
||||
for (int i=0;i<10;i++)
|
||||
{
|
||||
m_args[0].m_vrControllerEvents[controllerId].m_auxAnalogAxis[i] = auxAnalogAxes[i];
|
||||
}
|
||||
|
||||
m_args[0].m_csGUI->unlock();
|
||||
|
||||
}
|
||||
|
||||
@@ -339,6 +339,7 @@ enum b3VREventType
|
||||
VR_GENERIC_TRACKER_MOVE_EVENT=8,
|
||||
};
|
||||
|
||||
#define MAX_VR_ANALOG_AXIS 5
|
||||
#define MAX_VR_BUTTONS 64
|
||||
#define MAX_VR_CONTROLLERS 8
|
||||
|
||||
@@ -380,7 +381,7 @@ struct b3VRControllerEvent
|
||||
float m_orn[4];//valid for VR_CONTROLLER_MOVE_EVENT and VR_CONTROLLER_BUTTON_EVENT
|
||||
|
||||
float m_analogAxis;//valid if VR_CONTROLLER_MOVE_EVENT
|
||||
|
||||
float m_auxAnalogAxis[MAX_VR_ANALOG_AXIS*2];//store x,y per axis, only valid if VR_CONTROLLER_MOVE_EVENT
|
||||
int m_buttons[MAX_VR_BUTTONS];//valid if VR_CONTROLLER_BUTTON_EVENT, see b3VRButtonInfo
|
||||
};
|
||||
|
||||
|
||||
Reference in New Issue
Block a user