Add RtMidi for midi control, use the --midi option in premake, and see

update to OpenVR sdk 1.03 from https://github.com/ValveSoftware/openvr
add camPosX/Y/Z and camRotZ to adjust relative camera/world transform for VR (so you can align virtual table with real table etc)
tweak quadruped.py to move a bit
add mouse picking to physics server
This commit is contained in:
erwincoumans
2016-11-16 16:12:59 -08:00
parent b4b93573fc
commit 2329c00faa
32 changed files with 6434 additions and 398 deletions

View File

@@ -57,7 +57,7 @@
description = "Use Midi controller to control parameters"
}
-- --_OPTIONS["midi"] = "1";
-- _OPTIONS["midi"] = "1";
newoption
{
@@ -237,6 +237,7 @@ end
language "C++"
if not _OPTIONS["no-demos"] then
include "../examples/ExampleBrowser"
include "../examples/OpenGLWindow"
@@ -265,6 +266,10 @@ end
end
end
if _OPTIONS["midi"] then
include "../examples/ThirdPartyLibs/midi"
end
if not _OPTIONS["no-enet"] then
include "../examples/ThirdPartyLibs/enet"
include "../test/enet/nat_punchthrough/client"

View File

@@ -16,6 +16,6 @@ del tmp1234.txt
cd build3
premake4 --double --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../bin" vs2010
premake4 --double --midi --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../bin" vs2010
start vs2010

View File

@@ -2,14 +2,14 @@
# www.blender.org
mtllib plane.mtl
o Plane
v 5.000000 -5.000000 0.000000
v 5.000000 5.000000 0.000000
v -5.000000 5.000000 0.000000
v -5.000000 -5.000000 0.000000
v 15.000000 -15.000000 0.000000
v 15.000000 15.000000 0.000000
v -15.000000 15.000000 0.000000
v -15.000000 -15.000000 0.000000
vt 5.000000 0.000000
vt 5.000000 5.000000
vt 0.000000 5.000000
vt 15.000000 0.000000
vt 15.000000 15.000000
vt 0.000000 15.000000
vt 0.000000 0.000000
usemtl Material

View File

@@ -16,9 +16,9 @@
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<origin rpy="0 0 0" xyz="0 0 -5"/>
<geometry>
<box size="10 10 0.001"/>
<box size="30 30 10"/>
</geometry>
</collision>
</link>

View File

@@ -100,6 +100,10 @@ bool PhysicsClientSharedMemory::getBodyInfo(int bodyUniqueId, struct b3BodyInfo&
info.m_baseName = bodyJoints->m_baseName.c_str();
return true;
}
return false;
}
@@ -204,6 +208,32 @@ bool PhysicsClientSharedMemory::connect() {
b3Error("Cannot connect to shared memory");
return false;
}
#if 0
if (m_data->m_isConnected)
{
//get all existing bodies and body info...
SharedMemoryCommand& command = m_data->m_testBlock1->m_clientCommands[0];
//now transfer the information of the individual objects etc.
command.m_type = CMD_REQUEST_BODY_INFO;
command.m_sdfRequestInfoArgs.m_bodyUniqueId = 37;
submitClientCommand(command);
int timeout = 1024 * 1024 * 1024;
const SharedMemoryStatus* status = 0;
while ((status == 0) && (timeout-- > 0))
{
status = processServerStatus();
}
//submitClientCommand(command);
}
#endif
return true;
}

View File

@@ -43,8 +43,12 @@ bool gCloseToKuka=false;
bool gEnableRealTimeSimVR=false;
bool gCreateDefaultRobotAssets = false;
int gInternalSimFlags = 0;
int gHuskyId = -1;
btTransform huskyTr = btTransform::getIdentity();
int gCreateObjectSimVR = -1;
int gEnableKukaControl = 0;
btScalar simTimeScalingFactor = 1;
btScalar gRhsClamp = 1.f;
@@ -538,7 +542,7 @@ struct PhysicsServerCommandProcessorInternalData
m_kukaGripperMultiBody(0),
m_kukaGripperRevolute1(0),
m_kukaGripperRevolute2(0),
m_allowRealTimeSimulation(false),
m_allowRealTimeSimulation(true),
m_huskyId(-1),
m_KukaId(-1),
m_sphereId(-1),
@@ -704,7 +708,7 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
#endif
//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_dynamicsWorld->getCollisionObjectArray().reserve(32768);
m_data->m_remoteDebugDrawer = new SharedMemoryDebugDrawer();
@@ -3674,6 +3678,7 @@ void PhysicsServerCommandProcessor::physicsDebugDraw(int debugDrawFlags)
bool PhysicsServerCommandProcessor::pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld)
{
if (m_data->m_dynamicsWorld==0)
return false;
@@ -3707,7 +3712,7 @@ bool PhysicsServerCommandProcessor::pickBody(const btVector3& rayFromWorld, cons
} else
{
btMultiBodyLinkCollider* multiCol = (btMultiBodyLinkCollider*)btMultiBodyLinkCollider::upcast(rayCallback.m_collisionObject);
if (multiCol && multiCol->m_multiBody)
if (multiCol && multiCol->m_multiBody && multiCol->m_multiBody->getBaseMass()>0.)
{
m_data->m_prevCanSleep = multiCol->m_multiBody->getCanSleep();
@@ -3859,6 +3864,16 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
gSubStep = m_data->m_physicsDeltaTime;
}
if (gHuskyId >= 0)
{
InternalBodyHandle* bodyHandle = m_data->getHandle(gHuskyId);
if (bodyHandle && bodyHandle->m_multiBody)
{
huskyTr = bodyHandle->m_multiBody->getBaseWorldTransform();
}
}
int numSteps = m_data->m_dynamicsWorld->stepSimulation(dtInSec*simTimeScalingFactor,maxSteps, gSubStep);
gDroppedSimulationSteps += numSteps > maxSteps ? numSteps - maxSteps : 0;
@@ -3918,7 +3933,8 @@ void PhysicsServerCommandProcessor::createDefaultRobotAssets()
m_data->m_hasGround = true;
loadUrdf("plane.urdf", btVector3(0, 0, 0), btQuaternion(0, 0, 0, 1), true, true, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
loadUrdf("samurai.urdf", btVector3(0, 0, 0), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
// loadUrdf("samurai.urdf", btVector3(0, 0, 0), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
// loadUrdf("quadruped/quadruped.urdf", btVector3(2, 2, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
if (m_data->m_gripperRigidbodyFixed == 0)
{
@@ -4081,7 +4097,9 @@ void PhysicsServerCommandProcessor::createDefaultRobotAssets()
//loadUrdf("rook.urdf", btVector3(-1.2, 0, 0.7), btQuaternion(btVector3(1, 0, 0), SIMD_HALF_PI), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
//loadUrdf("knight.urdf", btVector3(-1.2, 0.2, 0.7), btQuaternion(btVector3(1, 0, 0), SIMD_HALF_PI), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
//loadUrdf("husky/husky.urdf", btVector3(2, -5, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
loadUrdf("husky/husky.urdf", btVector3(2, -5, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
gHuskyId = bodyId;
b3Printf("huskyId = %d", gHuskyId);
m_data->m_huskyId = bodyId;
m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, -10));
@@ -4184,7 +4202,7 @@ void PhysicsServerCommandProcessor::createDefaultRobotAssets()
q_new[5] = -SIMD_HALF_PI*0.66;
q_new[6] = 0;
if (gCloseToKuka)
if (gCloseToKuka && gEnableKukaControl)
{
double dampIk[6] = {1.0, 1.0, 1.0, 1.0, 1.0, 0.0};

View File

@@ -4,7 +4,9 @@
#include "PhysicsServerExample.h"
#ifdef B3_USE_MIDI
#include "RtMidi.h"
#endif//B3_USE_MIDI
#include "PhysicsServerSharedMemory.h"
#include "Bullet3Common/b3CommandLineArgs.h"
@@ -24,7 +26,7 @@
//@todo(erwincoumans) those globals are hacks for a VR demo, move this to Python/pybullet!
extern btVector3 gLastPickPos;
btVector3 gVRTeleportPos(0,0,0);
btVector3 gVRTeleportPos1(0,0,0);
btQuaternion gVRTeleportOrn(0, 0, 0,1);
extern btVector3 gVRGripperPos;
extern btQuaternion gVRGripperOrn;
@@ -37,11 +39,60 @@ extern bool gEnableRealTimeSimVR;
extern bool gCreateDefaultRobotAssets;
extern int gInternalSimFlags;
extern int gCreateObjectSimVR;
static int gGraspingController = -1;
extern int gEnableKukaControl;
int gGraspingController = -1;
extern btScalar simTimeScalingFactor;
extern bool gVRGripperClosed;
#if B3_USE_MIDI
#include <vector>
static float getParamf(float rangeMin, float rangeMax, int midiVal)
{
float v = rangeMin + (rangeMax - rangeMin)* (float(midiVal / 127.));
return v;
}
void midiCallback(double deltatime, std::vector< unsigned char > *message, void *userData)
{
unsigned int nBytes = message->size();
for (unsigned int i = 0; i<nBytes; i++)
std::cout << "Byte " << i << " = " << (int)message->at(i) << ", ";
if (nBytes > 0)
std::cout << "stamp = " << deltatime << std::endl;
if (nBytes > 2)
{
if (message->at(0) == 176)
{
if (message->at(1) == 16)
{
float rotZ = getParamf(-3.1415, 3.1415, message->at(2));
gVRTeleportOrn = btQuaternion(btVector3(0, 0, 1), rotZ);
b3Printf("gVRTeleportOrn rotZ = %f\n", rotZ);
}
if (message->at(1) == 32)
{
gCreateDefaultRobotAssets = 1;
}
for (int i = 0; i < 3; i++)
{
if (message->at(1) == i)
{
gVRTeleportPos1[i] = getParamf(-2, 2, message->at(2));
b3Printf("gVRTeleportPos[%d] = %f\n", i,gVRTeleportPos1[i]);
}
}
}
}
}
#endif //B3_USE_MIDI
bool gDebugRenderToggle = false;
void MotionThreadFunc(void* userPtr,void* lsMemory);
@@ -112,7 +163,19 @@ b3ThreadSupportInterface* createMotionThreadSupport(int numThreads)
}
#endif
enum MyMouseCommandType
{
MyMouseMove = 1,
MyMouseButtonDown,
MyMouseButtonUp
};
struct MyMouseCommand
{
btVector3 m_rayFrom;
btVector3 m_rayTo;
int m_type;
};
struct MotionArgs
{
@@ -128,6 +191,8 @@ struct MotionArgs
}
}
b3CriticalSection* m_cs;
btAlignedObjectArray<MyMouseCommand> m_mouseCommands;
PhysicsServerSharedMemory* m_physicsServerPtr;
b3AlignedObjectArray<b3Vector3> m_positions;
@@ -197,31 +262,31 @@ void MotionThreadFunc(void* userPtr,void* lsMemory)
btMatrix3x3 mat(args->m_vrControllerOrn[c]);
btScalar pickDistance = 1000.;
btVector3 toX = from+mat.getColumn(0);
btVector3 toY = from+mat.getColumn(1);
btVector3 toZ = from+mat.getColumn(2)*pickDistance;
btVector3 to = from+mat.getColumn(0)*pickDistance;
// btVector3 toY = from+mat.getColumn(1)*pickDistance;
// btVector3 toZ = from+mat.getColumn(2)*pickDistance;
if (args->m_isVrControllerTeleporting[c])
{
args->m_isVrControllerTeleporting[c] = false;
args->m_physicsServerPtr->pickBody(from,-toZ);
args->m_physicsServerPtr->pickBody(from, to);
args->m_physicsServerPtr->removePickingConstraint();
}
if (!gCloseToKuka)
if (!gEnableKukaControl)
{
if (args->m_isVrControllerPicking[c])
{
args->m_isVrControllerPicking[c] = false;
args->m_isVrControllerDragging[c] = true;
args->m_physicsServerPtr->pickBody(from,-toZ);
args->m_physicsServerPtr->pickBody(from, to);
//printf("PICK!\n");
}
}
if (args->m_isVrControllerDragging[c])
{
args->m_physicsServerPtr->movePickedBody(from,-toZ);
args->m_physicsServerPtr->movePickedBody(from, to);
// printf(".");
}
@@ -247,6 +312,37 @@ void MotionThreadFunc(void* userPtr,void* lsMemory)
}
args->m_cs->lock();
for (int i = 0; i < args->m_mouseCommands.size(); i++)
{
switch (args->m_mouseCommands[i].m_type)
{
case MyMouseMove:
{
args->m_physicsServerPtr->movePickedBody(args->m_mouseCommands[i].m_rayFrom, args->m_mouseCommands[i].m_rayTo);
break;
};
case MyMouseButtonDown:
{
args->m_physicsServerPtr->pickBody(args->m_mouseCommands[i].m_rayFrom, args->m_mouseCommands[i].m_rayTo);
break;
}
case MyMouseButtonUp:
{
args->m_physicsServerPtr->removePickingConstraint();
break;
}
default:
{
}
}
}
args->m_mouseCommands.clear();
args->m_cs->unlock();
args->m_physicsServerPtr->processClientCommands();
} while (args->m_cs->getSharedParam(0)!=eRequestTerminateMotion);
@@ -305,6 +401,7 @@ class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface
b3CriticalSection* m_cs;
public:
@@ -331,6 +428,7 @@ public:
int m_textureId;
int m_instanceId;
MultiThreadedOpenGLGuiHelper(CommonGraphicsApp* app, GUIHelperInterface* guiHelper)
:m_app(app)
@@ -498,7 +596,7 @@ public:
virtual CommonRenderInterface* getRenderInterface()
{
return 0;
return m_childGuiHelper->getRenderInterface();
}
virtual CommonGraphicsApp* getAppInterface()
@@ -680,7 +778,9 @@ class PhysicsServerExample : public SharedMemoryCommon
MotionArgs m_args[MAX_MOTION_NUM_THREADS];
MultiThreadedOpenGLGuiHelper* m_multiThreadedHelper;
bool m_wantsShutdown;
#ifdef B3_USE_MIDI
RtMidiIn* m_midi;
#endif
bool m_isConnected;
btClock m_clock;
bool m_replay;
@@ -740,8 +840,8 @@ public:
if (m_replay)
return false;
CommonRenderInterface* renderer = m_guiHelper->getRenderInterface();
CommonRenderInterface* renderer = m_multiThreadedHelper->m_childGuiHelper->getRenderInterface();// m_guiHelper->getRenderInterface();
if (!renderer)
{
return false;
@@ -750,7 +850,14 @@ public:
btVector3 rayTo = getRayTo(int(x), int(y));
btVector3 rayFrom;
renderer->getActiveCamera()->getCameraPosition(rayFrom);
m_physicsServer.movePickedBody(rayFrom,rayTo);
MyMouseCommand cmd;
cmd.m_rayFrom = rayFrom;
cmd.m_rayTo = rayTo;
cmd.m_type = MyMouseMove;
m_args[0].m_cs->lock();
m_args[0].m_mouseCommands.push_back(cmd);
m_args[0].m_cs->unlock();
return false;
};
@@ -779,7 +886,13 @@ public:
btVector3 rayFrom = camPos;
btVector3 rayTo = getRayTo(int(x),int(y));
m_physicsServer.pickBody(rayFrom, rayTo);
MyMouseCommand cmd;
cmd.m_rayFrom = rayFrom;
cmd.m_rayTo = rayTo;
cmd.m_type = MyMouseButtonDown;
m_args[0].m_cs->lock();
m_args[0].m_mouseCommands.push_back(cmd);
m_args[0].m_cs->unlock();
}
@@ -787,7 +900,14 @@ public:
{
if (button==0)
{
m_physicsServer.removePickingConstraint();
//m_physicsServer.removePickingConstraint();
MyMouseCommand cmd;
cmd.m_rayFrom.setValue(0,0,0);
cmd.m_rayTo.setValue(0, 0, 0);
cmd.m_type = MyMouseButtonUp;
m_args[0].m_cs->lock();
m_args[0].m_mouseCommands.push_back(cmd);
m_args[0].m_cs->unlock();
//remove p2p
}
}
@@ -805,6 +925,30 @@ public:
virtual void processCommandLineArgs(int argc, char* argv[])
{
b3CommandLineArgs args(argc,argv);
if (args.GetCmdLineArgument("camPosX", gVRTeleportPos1[0]))
{
printf("camPosX=%f\n", gVRTeleportPos1[0]);
}
if (args.GetCmdLineArgument("camPosY", gVRTeleportPos1[1]))
{
printf("camPosY=%f\n", gVRTeleportPos1[1]);
}
if (args.GetCmdLineArgument("camPosZ", gVRTeleportPos1[2]))
{
printf("camPosZ=%f\n", gVRTeleportPos1[2]);
}
float camRotZ = 0.f;
if (args.GetCmdLineArgument("camRotZ", camRotZ))
{
printf("camRotZ = %f\n", camRotZ);
btQuaternion ornZ(btVector3(0, 0, 1), camRotZ);
gVRTeleportOrn = ornZ;
}
if (args.CheckCmdLineFlag("robotassets"))
{
gCreateDefaultRobotAssets = true;
@@ -820,6 +964,40 @@ public:
};
#ifdef B3_USE_MIDI
static bool chooseMidiPort(RtMidiIn *rtmidi)
{
/*
std::cout << "\nWould you like to open a virtual input port? [y/N] ";
std::string keyHit;
std::getline( std::cin, keyHit );
if ( keyHit == "y" ) {
rtmidi->openVirtualPort();
return true;
}
*/
std::string portName;
unsigned int i = 0, nPorts = rtmidi->getPortCount();
if (nPorts == 0) {
std::cout << "No midi input ports available!" << std::endl;
return false;
}
if (nPorts > 0) {
std::cout << "\nOpening midi input port " << rtmidi->getPortName() << std::endl;
}
// std::getline( std::cin, keyHit ); // used to clear out stdin
rtmidi->openPort(i);
return true;
}
#endif //B3_USE_MIDI
PhysicsServerExample::PhysicsServerExample(MultiThreadedOpenGLGuiHelper* helper, SharedMemoryInterface* sharedMem, int options)
:SharedMemoryCommon(helper),
m_physicsServer(sharedMem),
@@ -831,6 +1009,14 @@ m_options(options)
,m_tinyVrGui(0)
#endif
{
#ifdef B3_USE_MIDI
m_midi = new RtMidiIn();
chooseMidiPort(m_midi);
m_midi->setCallback(&midiCallback);
// Don't ignore sysex, timing, or active sensing messages.
m_midi->ignoreTypes(false, false, false);
#endif
m_multiThreadedHelper = helper;
b3Printf("Started PhysicsServer\n");
}
@@ -839,6 +1025,10 @@ m_options(options)
PhysicsServerExample::~PhysicsServerExample()
{
#ifdef B3_USE_MIDI
delete m_midi;
m_midi = 0;
#endif
#ifdef BT_ENABLE_VR
delete m_tinyVrGui;
#endif
@@ -1159,10 +1349,25 @@ extern int gDroppedSimulationSteps;
extern int gNumSteps;
extern double gDtInSec;
extern double gSubStep;
extern int gHuskyId;
extern btTransform huskyTr;
void PhysicsServerExample::renderScene()
{
#if 0
///little VR test to follow/drive Husky vehicle
if (gHuskyId >= 0)
{
gVRTeleportPos1 = huskyTr.getOrigin();
gVRTeleportOrn = huskyTr.getRotation();
}
#endif
B3_PROFILE("PhysicsServerExample::RenderScene");
static char line0[1024];
static char line1[1024];
@@ -1275,9 +1480,27 @@ void PhysicsServerExample::renderScene()
//m_args[0].m_cs->lock();
//gVRTeleportPos[0] += 0.01;
vrOffset[12]=-gVRTeleportPos[0];
vrOffset[13]=-gVRTeleportPos[1];
vrOffset[14]=-gVRTeleportPos[2];
btTransform tr2a, tr2;
tr2a.setIdentity();
tr2.setIdentity();
tr2.setOrigin(gVRTeleportPos1);
tr2a.setRotation(gVRTeleportOrn);
btTransform trTotal = tr2*tr2a;
btTransform trInv = trTotal.inverse();
btMatrix3x3 vrOffsetRot;
vrOffsetRot.setRotation(trInv.getRotation());
for (int i = 0; i < 3; i++)
{
for (int j = 0; j < 3; j++)
{
vrOffset[i + 4 * j] = vrOffsetRot[i][j];
}
}
vrOffset[12]= trInv.getOrigin()[0];
vrOffset[13]= trInv.getOrigin()[1];
vrOffset[14]= trInv.getOrigin()[2];
this->m_multiThreadedHelper->m_childGuiHelper->getRenderInterface()->
getActiveCamera()->setVRCameraOffsetTransform(vrOffset);
@@ -1314,54 +1537,8 @@ void PhysicsServerExample::renderScene()
gEnableRealTimeSimVR = true;
}
if (gDebugRenderToggle)
if (m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->isVRCamera())
{
B3_PROFILE("Draw Debug HUD");
//some little experiment to add text/HUD to a VR camera (HTC Vive/Oculus Rift)
float pos[4];
m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->getCameraTargetPosition(pos);
pos[0]+=gVRTeleportPos[0];
pos[1]+=gVRTeleportPos[1];
pos[2]+=gVRTeleportPos[2];
btTransform viewTr;
btScalar m[16];
float mf[16];
m_guiHelper->getAppInterface()->m_renderer->getActiveCamera()->getCameraViewMatrix(mf);
for (int i=0;i<16;i++)
{
m[i] = mf[i];
}
m[12]=+gVRTeleportPos[0];
m[13]=+gVRTeleportPos[1];
m[14]=+gVRTeleportPos[2];
viewTr.setFromOpenGLMatrix(m);
btTransform viewTrInv = viewTr.inverse();
btVector3 side = viewTrInv.getBasis().getColumn(0);
btVector3 up = viewTrInv.getBasis().getColumn(1);
btVector3 fwd = viewTrInv.getBasis().getColumn(2);
float upMag = 0;
float sideMag = 2.2;
float fwdMag = -4;
m_guiHelper->getAppInterface()->drawText3D(line0,pos[0]+upMag*up[0]-sideMag*side[0]+fwdMag*fwd[0],pos[1]+upMag*up[1]-sideMag*side[1]+fwdMag*fwd[1],pos[2]+upMag*up[2]-sideMag*side[2]+fwdMag*fwd[2],1);
//btVector3 fwd = viewTrInv.getBasis().getColumn(2);
up = viewTrInv.getBasis().getColumn(1);
upMag = -0.3;
m_guiHelper->getAppInterface()->drawText3D(line1,pos[0]+upMag*up[0]-sideMag*side[0]+fwdMag*fwd[0],pos[1]+upMag*up[1]-sideMag*side[1]+fwdMag*fwd[1],pos[2]+upMag*up[2]-sideMag*side[2]+fwdMag*fwd[2],1);
}
//m_args[0].m_cs->unlock();
}
@@ -1482,7 +1659,7 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt
{
if (button == 1 && state == 0)
{
gVRTeleportPos = gLastPickPos;
// gVRTeleportPos = gLastPickPos;
}
} else
{
@@ -1515,9 +1692,19 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt
}
}
if (button==32 && state==0)
{
gCreateObjectSimVR = 1;
if (controllerId == gGraspingController)
{
gCreateObjectSimVR = 1;
}
else
{
gEnableKukaControl = !gEnableKukaControl;
}
}
@@ -1538,16 +1725,41 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt
m_args[0].m_isVrControllerPicking[controllerId] = (state != 0);
m_args[0].m_isVrControllerReleasing[controllerId] = (state == 0);
}
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;
if ((button == 33) || (button == 1))
{
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_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_vrControllerPos[controllerId] = trTotal.getOrigin();
m_args[0].m_vrControllerOrn[controllerId] = trTotal.getRotation();
}
}
}
void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[4], float orn[4], float analogAxis)
{
@@ -1558,22 +1770,44 @@ void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[
printf("Controller Id exceeds max: %d > %d", controllerId, MAX_VR_CONTROLLERS);
return;
}
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;
if (controllerId == gGraspingController)
{
gVRGripperAnalog = analogAxis;
gVRGripperPos.setValue(pos[0] + gVRTeleportPos[0], pos[1] + gVRTeleportPos[1], pos[2] + gVRTeleportPos[2]);
btQuaternion orgOrn(orn[0], orn[1], orn[2], orn[3]);
gVRGripperOrn = orgOrn*btQuaternion(btVector3(0, 0, 1), SIMD_HALF_PI)*btQuaternion(btVector3(0, 1, 0), SIMD_HALF_PI);
gVRGripperPos = trTotal.getOrigin();
gVRGripperOrn = trTotal.getRotation();
}
else
{
gVRGripper2Analog = analogAxis;
gVRController2Pos.setValue(pos[0] + gVRTeleportPos[0], pos[1] + gVRTeleportPos[1], pos[2] + gVRTeleportPos[2]);
btQuaternion orgOrn(orn[0], orn[1], orn[2], orn[3]);
gVRController2Orn = orgOrn*btQuaternion(btVector3(0, 0, 1), SIMD_HALF_PI)*btQuaternion(btVector3(0, 1, 0), SIMD_HALF_PI);
gVRController2Pos = trTotal.getOrigin();
gVRController2Orn = trTotal.getRotation();
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_vrControllerPos[controllerId] = trTotal.getOrigin();
m_args[0].m_vrControllerOrn[controllerId] = trTotal.getRotation();
}
}

View File

@@ -30,7 +30,7 @@ public:
//bool supportsJointMotor(class btMultiBody* body, int linkIndex);
//@todo(erwincoumans) Should we have shared memory commands for picking objects?
///The pickBody method will try to pick the first body along a ray, return true if succeeds, false otherwise
virtual bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld);
virtual bool movePickedBody(const btVector3& rayFromWorld, const btVector3& rayToWorld);

View File

@@ -154,6 +154,37 @@ links {
language "C++"
if _OPTIONS["midi"] then
defines {"B3_USE_MIDI"}
includedirs{"../ThirdPartyLibs/midi"}
files {
"../ThirdPartyLibs/midi/RtMidi.cpp",
"../ThirdPartyLibs/midi/RtMidi.h",
"../ThirdPartyLibs/midi/RtError.h",
}
if os.is("Windows") then
links {"winmm"}
defines {"__WINDOWS_MM__", "WIN32"}
end
if os.is("Linux") then
defines {"__LINUX_ALSA__"}
links {"asound","pthread"}
end
if os.is("MacOSX") then
links{"CoreAudio.framework", "coreMIDI.framework", "Cocoa.framework"}
defines {"__MACOSX_CORE__"}
end
end
files {
myfiles,
"../StandaloneMain/main_opengl_single_example.cpp",
@@ -213,7 +244,37 @@ if os.is("Windows") then
else
kind "ConsoleApp"
end
if _OPTIONS["midi"] then
defines {"B3_USE_MIDI"}
includedirs{"../ThirdPartyLibs/midi"}
files {
"../ThirdPartyLibs/midi/RtMidi.cpp",
"../ThirdPartyLibs/midi/RtMidi.h",
"../ThirdPartyLibs/midi/RtError.h",
}
if os.is("Windows") then
links {"winmm"}
defines {"__WINDOWS_MM__", "WIN32"}
end
if os.is("Linux") then
defines {"__LINUX_ALSA__"}
links {"asound","pthread"}
end
if os.is("MacOSX") then
links{"CoreAudio.framework", "coreMIDI.framework", "Cocoa.framework"}
defines {"__MACOSX_CORE__"}
end
end
includedirs {
".","../../src", "../ThirdPartyLibs",
"../ThirdPartyLibs/openvr/headers",

View File

@@ -1,11 +1,14 @@
#ifdef BT_ENABLE_VR
//#define BT_USE_CUSTOM_PROFILER
#ifdef BT_USE_CUSTOM_PROFILER
#endif
//========= Copyright Valve Corporation ============//
#include "../OpenGLWindow/SimpleOpenGL3App.h"
#include "../OpenGLWindow/OpenGLInclude.h"
#include "Bullet3Common/b3Quaternion.h"
#include "Bullet3Common/b3Transform.h"
#include "Bullet3Common/b3CommandLineArgs.h"
#include "../ExampleBrowser/OpenGLGuiHelper.h"
@@ -776,12 +779,14 @@ void CMainApplication::RunMainLoop()
while ( !bQuit && !m_app->m_window->requestedExit())
{
{
B3_PROFILE("main");
bQuit = HandleInput();
RenderFrame();
}
}
}
@@ -1282,6 +1287,8 @@ void CMainApplication::AddCubeToScene( Matrix4 mat, std::vector<float> &vertdata
//-----------------------------------------------------------------------------
// Purpose: Draw all of the controllers as X/Y/Z lines
//-----------------------------------------------------------------------------
extern int gGraspingController;
void CMainApplication::DrawControllers()
{
// don't draw controllers if somebody else has input focus
@@ -1295,6 +1302,8 @@ void CMainApplication::DrawControllers()
for ( vr::TrackedDeviceIndex_t unTrackedDevice = vr::k_unTrackedDeviceIndex_Hmd + 1; unTrackedDevice < vr::k_unMaxTrackedDeviceCount; ++unTrackedDevice )
{
if ( !m_pHMD->IsTrackedDeviceConnected( unTrackedDevice ) )
continue;
@@ -2183,9 +2192,11 @@ void CGLRenderModel::Draw()
//-----------------------------------------------------------------------------
int main(int argc, char *argv[])
{
#ifdef BT_USE_CUSTOM_PROFILER
//b3SetCustomEnterProfileZoneFunc(...);
//b3SetCustomLeaveProfileZoneFunc(...);
b3SetCustomEnterProfileZoneFunc(dcEnter);
b3SetCustomLeaveProfileZoneFunc(dcLeave);
#endif
@@ -2223,7 +2234,6 @@ int main(int argc, char *argv[])
pMainApplication->Shutdown();
#ifdef BT_USE_CUSTOM_PROFILER
//...
#endif
return 0;

View File

@@ -83,8 +83,11 @@ int main(int argc, char* argv[])
//DummyGUIHelper gui;
CommonExampleOptions options(&gui);
example = StandaloneExampleCreateFunc(options);
example->processCommandLineArgs(argc, argv);
example->initPhysics();
example->resetCamera();

View File

@@ -0,0 +1,29 @@
RtMidi WWW site: http://music.mcgill.ca/~gary/rtmidi/
RtMidi: realtime MIDI i/o C++ classes
Copyright (c) 2003-2012 Gary P. Scavone
Permission is hereby granted, free of charge, to any person
obtaining a copy of this software and associated documentation files
(the "Software"), to deal in the Software without restriction,
including without limitation the rights to use, copy, modify, merge,
publish, distribute, sublicense, and/or sell copies of the Software,
and to permit persons to whom the Software is furnished to do so,
subject to the following conditions:
The above copyright notice and this permission notice shall be
included in all copies or substantial portions of the Software.
Any person wishing to distribute modifications to the Software is
asked to send the modifications to the original developer so that
they can be incorporated into the canonical version. This is,
however, not a binding provision of this license.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.
IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR
ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF
CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION
WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*/

View File

@@ -0,0 +1,60 @@
/************************************************************************/
/*! \class RtError
\brief Exception handling class for RtAudio & RtMidi.
The RtError class is quite simple but it does allow errors to be
"caught" by RtError::Type. See the RtAudio and RtMidi
documentation to know which methods can throw an RtError.
*/
/************************************************************************/
#ifndef RTERROR_H
#define RTERROR_H
#include <exception>
#include <iostream>
#include <string>
class RtError : public std::exception
{
public:
//! Defined RtError types.
enum Type {
WARNING, /*!< A non-critical error. */
DEBUG_WARNING, /*!< A non-critical error which might be useful for debugging. */
UNSPECIFIED, /*!< The default, unspecified error type. */
NO_DEVICES_FOUND, /*!< No devices found on system. */
INVALID_DEVICE, /*!< An invalid device ID was specified. */
MEMORY_ERROR, /*!< An error occured during memory allocation. */
INVALID_PARAMETER, /*!< An invalid parameter was specified to a function. */
INVALID_USE, /*!< The function was called incorrectly. */
DRIVER_ERROR, /*!< A system driver error occured. */
SYSTEM_ERROR, /*!< A system error occured. */
THREAD_ERROR /*!< A thread error occured. */
};
//! The constructor.
RtError(const std::string& message, Type type = RtError::UNSPECIFIED) throw() : message_(message), type_(type) {}
//! The destructor.
virtual ~RtError(void) throw() {}
//! Prints thrown error message to stderr.
virtual void printMessage(void) const throw() { std::cerr << '\n' << message_ << "\n\n"; }
//! Returns the thrown error message type.
virtual const Type& getType(void) const throw() { return type_; }
//! Returns the thrown error message string.
virtual const std::string& getMessage(void) const throw() { return message_; }
//! Returns the thrown error message as a c-style string.
virtual const char* what(void) const throw() { return message_.c_str(); }
protected:
std::string message_;
Type type_;
};
#endif

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,675 @@
/**********************************************************************/
/*! \class RtMidi
\brief An abstract base class for realtime MIDI input/output.
This class implements some common functionality for the realtime
MIDI input/output subclasses RtMidiIn and RtMidiOut.
RtMidi WWW site: http://music.mcgill.ca/~gary/rtmidi/
RtMidi: realtime MIDI i/o C++ classes
Copyright (c) 2003-2012 Gary P. Scavone
Permission is hereby granted, free of charge, to any person
obtaining a copy of this software and associated documentation files
(the "Software"), to deal in the Software without restriction,
including without limitation the rights to use, copy, modify, merge,
publish, distribute, sublicense, and/or sell copies of the Software,
and to permit persons to whom the Software is furnished to do so,
subject to the following conditions:
The above copyright notice and this permission notice shall be
included in all copies or substantial portions of the Software.
Any person wishing to distribute modifications to the Software is
asked to send the modifications to the original developer so that
they can be incorporated into the canonical version. This is,
however, not a binding provision of this license.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.
IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR
ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF
CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION
WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*/
/**********************************************************************/
/*!
\file RtMidi.h
*/
// RtMidi: Version 2.0.1
#ifndef RTMIDI_H
#define RTMIDI_H
#include "RtError.h"
#include <string>
#include <vector>
class RtMidi
{
public:
//! MIDI API specifier arguments.
enum Api {
UNSPECIFIED, /*!< Search for a working compiled API. */
MACOSX_CORE, /*!< Macintosh OS-X Core Midi API. */
LINUX_ALSA, /*!< The Advanced Linux Sound Architecture API. */
UNIX_JACK, /*!< The Jack Low-Latency MIDI Server API. */
WINDOWS_MM, /*!< The Microsoft Multimedia MIDI API. */
WINDOWS_KS, /*!< The Microsoft Kernel Streaming MIDI API. */
RTMIDI_DUMMY /*!< A compilable but non-functional API. */
};
//! A static function to determine the available compiled MIDI APIs.
/*!
The values returned in the std::vector can be compared against
the enumerated list values. Note that there can be more than one
API compiled for certain operating systems.
*/
static void getCompiledApi( std::vector<RtMidi::Api> &apis );
//! Pure virtual openPort() function.
virtual void openPort( unsigned int portNumber = 0, const std::string portName = std::string( "RtMidi" ) ) = 0;
//! Pure virtual openVirtualPort() function.
virtual void openVirtualPort( const std::string portName = std::string( "RtMidi" ) ) = 0;
//! Pure virtual getPortCount() function.
virtual unsigned int getPortCount() = 0;
//! Pure virtual getPortName() function.
virtual std::string getPortName( unsigned int portNumber = 0 ) = 0;
//! Pure virtual closePort() function.
virtual void closePort( void ) = 0;
//! A basic error reporting function for RtMidi classes.
static void error( RtError::Type type, std::string errorString );
protected:
RtMidi() {};
virtual ~RtMidi() {};
};
/**********************************************************************/
/*! \class RtMidiIn
\brief A realtime MIDI input class.
This class provides a common, platform-independent API for
realtime MIDI input. It allows access to a single MIDI input
port. Incoming MIDI messages are either saved to a queue for
retrieval using the getMessage() function or immediately passed to
a user-specified callback function. Create multiple instances of
this class to connect to more than one MIDI device at the same
time. With the OS-X and Linux ALSA MIDI APIs, it is also possible
to open a virtual input port to which other MIDI software clients
can connect.
by Gary P. Scavone, 2003-2012.
*/
/**********************************************************************/
// **************************************************************** //
//
// RtMidiIn and RtMidiOut class declarations.
//
// RtMidiIn / RtMidiOut are "controllers" used to select an available
// MIDI input or output interface. They present common APIs for the
// user to call but all functionality is implemented by the classes
// MidiInApi, MidiOutApi and their subclasses. RtMidiIn and RtMidiOut
// each create an instance of a MidiInApi or MidiOutApi subclass based
// on the user's API choice. If no choice is made, they attempt to
// make a "logical" API selection.
//
// **************************************************************** //
class MidiInApi;
class MidiOutApi;
class RtMidiIn : public RtMidi
{
public:
//! User callback function type definition.
typedef void (*RtMidiCallback)( double timeStamp, std::vector<unsigned char> *message, void *userData);
//! Default constructor that allows an optional api, client name and queue size.
/*!
An assert will be fired if a MIDI system initialization
error occurs. The queue size defines the maximum number of
messages that can be held in the MIDI queue (when not using a
callback function). If the queue size limit is reached,
incoming messages will be ignored.
If no API argument is specified and multiple API support has been
compiled, the default order of use is JACK, ALSA (Linux) and CORE,
Jack (OS-X).
*/
RtMidiIn( RtMidi::Api api=UNSPECIFIED,
const std::string clientName = std::string( "RtMidi Input Client"),
unsigned int queueSizeLimit = 100 );
//! If a MIDI connection is still open, it will be closed by the destructor.
~RtMidiIn ( void );
//! Returns the MIDI API specifier for the current instance of RtMidiIn.
RtMidi::Api getCurrentApi( void );
//! Open a MIDI input connection.
/*!
An optional port number greater than 0 can be specified.
Otherwise, the default or first port found is opened.
*/
void openPort( unsigned int portNumber = 0, const std::string portName = std::string( "RtMidi Input" ) );
//! Create a virtual input port, with optional name, to allow software connections (OS X and ALSA only).
/*!
This function creates a virtual MIDI input port to which other
software applications can connect. This type of functionality
is currently only supported by the Macintosh OS-X and Linux ALSA
APIs (the function does nothing for the other APIs).
*/
void openVirtualPort( const std::string portName = std::string( "RtMidi Input" ) );
//! Set a callback function to be invoked for incoming MIDI messages.
/*!
The callback function will be called whenever an incoming MIDI
message is received. While not absolutely necessary, it is best
to set the callback function before opening a MIDI port to avoid
leaving some messages in the queue.
*/
void setCallback( RtMidiCallback callback, void *userData = 0 );
//! Cancel use of the current callback function (if one exists).
/*!
Subsequent incoming MIDI messages will be written to the queue
and can be retrieved with the \e getMessage function.
*/
void cancelCallback();
//! Close an open MIDI connection (if one exists).
void closePort( void );
//! Return the number of available MIDI input ports.
unsigned int getPortCount();
//! Return a string identifier for the specified MIDI input port number.
/*!
An empty string is returned if an invalid port specifier is provided.
*/
std::string getPortName( unsigned int portNumber = 0 );
//! Specify whether certain MIDI message types should be queued or ignored during input.
/*!
o By default, MIDI timing and active sensing messages are ignored
during message input because of their relative high data rates.
MIDI sysex messages are ignored by default as well. Variable
values of "true" imply that the respective message type will be
ignored.
*/
void ignoreTypes( bool midiSysex = true, bool midiTime = true, bool midiSense = true );
//! Fill the user-provided vector with the data bytes for the next available MIDI message in the input queue and return the event delta-time in seconds.
/*!
This function returns immediately whether a new message is
available or not. A valid message is indicated by a non-zero
vector size. An assert is fired if an error occurs during
message retrieval or an input connection was not previously
established.
*/
double getMessage( std::vector<unsigned char> *message );
protected:
void openMidiApi( RtMidi::Api api, const std::string clientName, unsigned int queueSizeLimit );
MidiInApi *rtapi_;
};
/**********************************************************************/
/*! \class RtMidiOut
\brief A realtime MIDI output class.
This class provides a common, platform-independent API for MIDI
output. It allows one to probe available MIDI output ports, to
connect to one such port, and to send MIDI bytes immediately over
the connection. Create multiple instances of this class to
connect to more than one MIDI device at the same time. With the
OS-X and Linux ALSA MIDI APIs, it is also possible to open a
virtual port to which other MIDI software clients can connect.
by Gary P. Scavone, 2003-2012.
*/
/**********************************************************************/
class RtMidiOut : public RtMidi
{
public:
//! Default constructor that allows an optional client name.
/*!
An exception will be thrown if a MIDI system initialization error occurs.
If no API argument is specified and multiple API support has been
compiled, the default order of use is JACK, ALSA (Linux) and CORE,
Jack (OS-X).
*/
RtMidiOut( RtMidi::Api api=UNSPECIFIED,
const std::string clientName = std::string( "RtMidi Output Client") );
//! The destructor closes any open MIDI connections.
~RtMidiOut( void );
//! Returns the MIDI API specifier for the current instance of RtMidiOut.
RtMidi::Api getCurrentApi( void );
//! Open a MIDI output connection.
/*!
An optional port number greater than 0 can be specified.
Otherwise, the default or first port found is opened. An
exception is thrown if an error occurs while attempting to make
the port connection.
*/
void openPort( unsigned int portNumber = 0, const std::string portName = std::string( "RtMidi Output" ) );
//! Close an open MIDI connection (if one exists).
void closePort( void );
//! Create a virtual output port, with optional name, to allow software connections (OS X and ALSA only).
/*!
This function creates a virtual MIDI output port to which other
software applications can connect. This type of functionality
is currently only supported by the Macintosh OS-X and Linux ALSA
APIs (the function does nothing with the other APIs). An
exception is thrown if an error occurs while attempting to create
the virtual port.
*/
void openVirtualPort( const std::string portName = std::string( "RtMidi Output" ) );
//! Return the number of available MIDI output ports.
unsigned int getPortCount( void );
//! Return a string identifier for the specified MIDI port type and number.
/*!
An empty string is returned if an invalid port specifier is provided.
*/
std::string getPortName( unsigned int portNumber = 0 );
//! Immediately send a single message out an open MIDI output port.
/*!
An exception is thrown if an error occurs during output or an
output connection was not previously established.
*/
void sendMessage( std::vector<unsigned char> *message );
protected:
void openMidiApi( RtMidi::Api api, const std::string clientName );
MidiOutApi *rtapi_;
};
// **************************************************************** //
//
// MidiInApi / MidiOutApi class declarations.
//
// Subclasses of MidiInApi and MidiOutApi contain all API- and
// OS-specific code necessary to fully implement the RtMidi API.
//
// Note that MidiInApi and MidiOutApi are abstract base classes and
// cannot be explicitly instantiated. RtMidiIn and RtMidiOut will
// create instances of a MidiInApi or MidiOutApi subclass.
//
// **************************************************************** //
class MidiInApi
{
public:
MidiInApi( unsigned int queueSizeLimit );
virtual ~MidiInApi( void );
virtual RtMidi::Api getCurrentApi( void ) = 0;
virtual void openPort( unsigned int portNumber, const std::string portName ) = 0;
virtual void openVirtualPort( const std::string portName ) = 0;
virtual void closePort( void ) = 0;
void setCallback( RtMidiIn::RtMidiCallback callback, void *userData );
void cancelCallback( void );
virtual unsigned int getPortCount( void ) = 0;
virtual std::string getPortName( unsigned int portNumber ) = 0;
virtual void ignoreTypes( bool midiSysex, bool midiTime, bool midiSense );
double getMessage( std::vector<unsigned char> *message );
// A MIDI structure used internally by the class to store incoming
// messages. Each message represents one and only one MIDI message.
struct MidiMessage {
std::vector<unsigned char> bytes;
double timeStamp;
// Default constructor.
MidiMessage()
:bytes(0), timeStamp(0.0) {}
};
struct MidiQueue {
unsigned int front;
unsigned int back;
unsigned int size;
unsigned int ringSize;
MidiMessage *ring;
// Default constructor.
MidiQueue()
:front(0), back(0), size(0), ringSize(0) {}
};
// The RtMidiInData structure is used to pass private class data to
// the MIDI input handling function or thread.
struct RtMidiInData {
MidiQueue queue;
MidiMessage message;
unsigned char ignoreFlags;
bool doInput;
bool firstMessage;
void *apiData;
bool usingCallback;
void *userCallback;
void *userData;
bool continueSysex;
// Default constructor.
RtMidiInData()
: ignoreFlags(7), doInput(false), firstMessage(true),
apiData(0), usingCallback(false), userCallback(0), userData(0),
continueSysex(false) {}
};
protected:
virtual void initialize( const std::string& clientName ) = 0;
RtMidiInData inputData_;
void *apiData_;
bool connected_;
std::string errorString_;
};
class MidiOutApi
{
public:
MidiOutApi( void );
virtual ~MidiOutApi( void );
virtual RtMidi::Api getCurrentApi( void ) = 0;
virtual void openPort( unsigned int portNumber, const std::string portName ) = 0;
virtual void openVirtualPort( const std::string portName ) = 0;
virtual void closePort( void ) = 0;
virtual unsigned int getPortCount( void ) = 0;
virtual std::string getPortName( unsigned int portNumber ) = 0;
virtual void sendMessage( std::vector<unsigned char> *message ) = 0;
protected:
virtual void initialize( const std::string& clientName ) = 0;
void *apiData_;
bool connected_;
std::string errorString_;
};
// **************************************************************** //
//
// Inline RtMidiIn and RtMidiOut definitions.
//
// **************************************************************** //
inline RtMidi::Api RtMidiIn :: getCurrentApi( void ) { return rtapi_->getCurrentApi(); }
inline void RtMidiIn :: openPort( unsigned int portNumber, const std::string portName ) { return rtapi_->openPort( portNumber, portName ); }
inline void RtMidiIn :: openVirtualPort( const std::string portName ) { return rtapi_->openVirtualPort( portName ); }
inline void RtMidiIn :: closePort( void ) { return rtapi_->closePort(); }
inline void RtMidiIn :: setCallback( RtMidiCallback callback, void *userData ) { return rtapi_->setCallback( callback, userData ); }
inline void RtMidiIn :: cancelCallback( void ) { return rtapi_->cancelCallback(); }
inline unsigned int RtMidiIn :: getPortCount( void ) { return rtapi_->getPortCount(); }
inline std::string RtMidiIn :: getPortName( unsigned int portNumber ) { return rtapi_->getPortName( portNumber ); }
inline void RtMidiIn :: ignoreTypes( bool midiSysex, bool midiTime, bool midiSense ) { return rtapi_->ignoreTypes( midiSysex, midiTime, midiSense ); }
inline double RtMidiIn :: getMessage( std::vector<unsigned char> *message ) { return rtapi_->getMessage( message ); }
inline RtMidi::Api RtMidiOut :: getCurrentApi( void ) { return rtapi_->getCurrentApi(); }
inline void RtMidiOut :: openPort( unsigned int portNumber, const std::string portName ) { return rtapi_->openPort( portNumber, portName ); }
inline void RtMidiOut :: openVirtualPort( const std::string portName ) { return rtapi_->openVirtualPort( portName ); }
inline void RtMidiOut :: closePort( void ) { return rtapi_->closePort(); }
inline unsigned int RtMidiOut :: getPortCount( void ) { return rtapi_->getPortCount(); }
inline std::string RtMidiOut :: getPortName( unsigned int portNumber ) { return rtapi_->getPortName( portNumber ); }
inline void RtMidiOut :: sendMessage( std::vector<unsigned char> *message ) { return rtapi_->sendMessage( message ); }
// **************************************************************** //
//
// MidiInApi and MidiOutApi subclass prototypes.
//
// **************************************************************** //
#if !defined(__LINUX_ALSA__) && !defined(__UNIX_JACK__) && !defined(__MACOSX_CORE__) && !defined(__WINDOWS_MM__) && !defined(__WINDOWS_KS__)
#define __RTMIDI_DUMMY__
#endif
#if defined(__MACOSX_CORE__)
class MidiInCore: public MidiInApi
{
public:
MidiInCore( const std::string clientName, unsigned int queueSizeLimit );
~MidiInCore( void );
RtMidi::Api getCurrentApi( void ) { return RtMidi::MACOSX_CORE; };
void openPort( unsigned int portNumber, const std::string portName );
void openVirtualPort( const std::string portName );
void closePort( void );
unsigned int getPortCount( void );
std::string getPortName( unsigned int portNumber );
protected:
void initialize( const std::string& clientName );
};
class MidiOutCore: public MidiOutApi
{
public:
MidiOutCore( const std::string clientName );
~MidiOutCore( void );
RtMidi::Api getCurrentApi( void ) { return RtMidi::MACOSX_CORE; };
void openPort( unsigned int portNumber, const std::string portName );
void openVirtualPort( const std::string portName );
void closePort( void );
unsigned int getPortCount( void );
std::string getPortName( unsigned int portNumber );
void sendMessage( std::vector<unsigned char> *message );
protected:
void initialize( const std::string& clientName );
};
#endif
#if defined(__UNIX_JACK__)
class MidiInJack: public MidiInApi
{
public:
MidiInJack( const std::string clientName, unsigned int queueSizeLimit );
~MidiInJack( void );
RtMidi::Api getCurrentApi( void ) { return RtMidi::UNIX_JACK; };
void openPort( unsigned int portNumber, const std::string portName );
void openVirtualPort( const std::string portName );
void closePort( void );
unsigned int getPortCount( void );
std::string getPortName( unsigned int portNumber );
protected:
void initialize( const std::string& clientName );
};
class MidiOutJack: public MidiOutApi
{
public:
MidiOutJack( const std::string clientName );
~MidiOutJack( void );
RtMidi::Api getCurrentApi( void ) { return RtMidi::UNIX_JACK; };
void openPort( unsigned int portNumber, const std::string portName );
void openVirtualPort( const std::string portName );
void closePort( void );
unsigned int getPortCount( void );
std::string getPortName( unsigned int portNumber );
void sendMessage( std::vector<unsigned char> *message );
protected:
void initialize( const std::string& clientName );
};
#endif
#if defined(__LINUX_ALSA__)
class MidiInAlsa: public MidiInApi
{
public:
MidiInAlsa( const std::string clientName, unsigned int queueSizeLimit );
~MidiInAlsa( void );
RtMidi::Api getCurrentApi( void ) { return RtMidi::LINUX_ALSA; };
void openPort( unsigned int portNumber, const std::string portName );
void openVirtualPort( const std::string portName );
void closePort( void );
unsigned int getPortCount( void );
std::string getPortName( unsigned int portNumber );
protected:
void initialize( const std::string& clientName );
};
class MidiOutAlsa: public MidiOutApi
{
public:
MidiOutAlsa( const std::string clientName );
~MidiOutAlsa( void );
RtMidi::Api getCurrentApi( void ) { return RtMidi::LINUX_ALSA; };
void openPort( unsigned int portNumber, const std::string portName );
void openVirtualPort( const std::string portName );
void closePort( void );
unsigned int getPortCount( void );
std::string getPortName( unsigned int portNumber );
void sendMessage( std::vector<unsigned char> *message );
protected:
void initialize( const std::string& clientName );
};
#endif
#if defined(__WINDOWS_MM__)
class MidiInWinMM: public MidiInApi
{
public:
MidiInWinMM( const std::string clientName, unsigned int queueSizeLimit );
~MidiInWinMM( void );
RtMidi::Api getCurrentApi( void ) { return RtMidi::WINDOWS_MM; };
void openPort( unsigned int portNumber, const std::string portName );
void openVirtualPort( const std::string portName );
void closePort( void );
unsigned int getPortCount( void );
std::string getPortName( unsigned int portNumber );
protected:
void initialize( const std::string& clientName );
};
class MidiOutWinMM: public MidiOutApi
{
public:
MidiOutWinMM( const std::string clientName );
~MidiOutWinMM( void );
RtMidi::Api getCurrentApi( void ) { return RtMidi::WINDOWS_MM; };
void openPort( unsigned int portNumber, const std::string portName );
void openVirtualPort( const std::string portName );
void closePort( void );
unsigned int getPortCount( void );
std::string getPortName( unsigned int portNumber );
void sendMessage( std::vector<unsigned char> *message );
protected:
void initialize( const std::string& clientName );
};
#endif
#if defined(__WINDOWS_KS__)
class MidiInWinKS: public MidiInApi
{
public:
MidiInWinKS( const std::string clientName, unsigned int queueSizeLimit );
~MidiInWinKS( void );
RtMidi::Api getCurrentApi( void ) { return RtMidi::WINDOWS_KS; };
void openPort( unsigned int portNumber, const std::string portName );
void openVirtualPort( const std::string portName );
void closePort( void );
unsigned int getPortCount( void );
std::string getPortName( unsigned int portNumber );
protected:
void initialize( const std::string& clientName );
};
class MidiOutWinKS: public MidiOutApi
{
public:
MidiOutWinKS( const std::string clientName );
~MidiOutWinKS( void );
RtMidi::Api getCurrentApi( void ) { return RtMidi::WINDOWS_KS; };
void openPort( unsigned int portNumber, const std::string portName );
void openVirtualPort( const std::string portName );
void closePort( void );
unsigned int getPortCount( void );
std::string getPortName( unsigned int portNumber );
void sendMessage( std::vector<unsigned char> *message );
protected:
void initialize( const std::string& clientName );
};
#endif
#if defined(__RTMIDI_DUMMY__)
class MidiInDummy: public MidiInApi
{
public:
MidiInDummy( const std::string clientName, unsigned int queueSizeLimit ) : MidiInApi( queueSizeLimit ) { errorString_ = "MidiInDummy: This class provides no functionality."; RtMidi::error( RtError::WARNING, errorString_ ); };
RtMidi::Api getCurrentApi( void ) { return RtMidi::RTMIDI_DUMMY; };
void openPort( unsigned int portNumber, const std::string portName ) {};
void openVirtualPort( const std::string portName ) {};
void closePort( void ) {};
unsigned int getPortCount( void ) { return 0; };
std::string getPortName( unsigned int portNumber ) { return ""; };
protected:
void initialize( const std::string& clientName ) {};
};
class MidiOutDummy: public MidiOutApi
{
public:
MidiOutDummy( const std::string clientName ) { errorString_ = "MidiOutDummy: This class provides no functionality."; RtMidi::error( RtError::WARNING, errorString_ ); };
RtMidi::Api getCurrentApi( void ) { return RtMidi::RTMIDI_DUMMY; };
void openPort( unsigned int portNumber, const std::string portName ) {};
void openVirtualPort( const std::string portName ) {};
void closePort( void ) {};
unsigned int getPortCount( void ) { return 0; };
std::string getPortName( unsigned int portNumber ) { return ""; };
void sendMessage( std::vector<unsigned char> *message ) {};
protected:
void initialize( const std::string& clientName ) {};
};
#endif
#endif

View File

@@ -0,0 +1,112 @@
//*****************************************//
// cmidiin.cpp
// by Gary Scavone, 2003-2004.
//
// Simple program to test MIDI input and
// use of a user callback function.
//
//*****************************************//
#include <iostream>
#include <cstdlib>
#include "RtMidi.h"
void usage( void ) {
// Error function in case of incorrect command-line
// argument specifications.
std::cout << "\nuseage: cmidiin <port>\n";
std::cout << " where port = the device to use (default = 0).\n\n";
exit( 0 );
}
void mycallback( double deltatime, std::vector< unsigned char > *message, void *userData )
{
unsigned int nBytes = message->size();
for ( unsigned int i=0; i<nBytes; i++ )
std::cout << "Byte " << i << " = " << (int)message->at(i) << ", ";
if ( nBytes > 0 )
std::cout << "stamp = " << deltatime << std::endl;
}
// This function should be embedded in a try/catch block in case of
// an exception. It offers the user a choice of MIDI ports to open.
// It returns false if there are no ports available.
bool chooseMidiPort( RtMidiIn *rtmidi );
int main( int argc, char *argv[] )
{
RtMidiIn *midiin = 0;
// Minimal command-line check.
if ( argc > 2 ) usage();
// RtMidiIn constructor
midiin = new RtMidiIn();
// Call function to select port.
if ( chooseMidiPort( midiin ) == false ) goto cleanup;
// Set our callback function. This should be done immediately after
// opening the port to avoid having incoming messages written to the
// queue instead of sent to the callback function.
midiin->setCallback( &mycallback );
// Don't ignore sysex, timing, or active sensing messages.
midiin->ignoreTypes( false, false, false );
std::cout << "\nReading MIDI input ... press <enter> to quit.\n";
char input;
std::cin.get(input);
std::cin.get(input);
cleanup:
delete midiin;
return 0;
}
bool chooseMidiPort( RtMidiIn *rtmidi )
{
/*
std::cout << "\nWould you like to open a virtual input port? [y/N] ";
std::string keyHit;
std::getline( std::cin, keyHit );
if ( keyHit == "y" ) {
rtmidi->openVirtualPort();
return true;
}
*/
std::string portName;
unsigned int i = 0, nPorts = rtmidi->getPortCount();
if ( nPorts == 0 ) {
std::cout << "No input ports available!" << std::endl;
return false;
}
if ( nPorts == 1 ) {
std::cout << "\nOpening " << rtmidi->getPortName() << std::endl;
}
else {
for ( i=0; i<nPorts; i++ ) {
portName = rtmidi->getPortName(i);
std::cout << " Input port #" << i << ": " << portName << '\n';
}
do {
std::cout << "\nChoose a port number: ";
std::cin >> i;
} while ( i >= nPorts );
}
// std::getline( std::cin, keyHit ); // used to clear out stdin
rtmidi->openPort( i );
return true;
}

View File

@@ -0,0 +1,35 @@
project "rtMidiTest"
kind "ConsoleApp"
-- defines { }
includedirs
{
".",
}
-- links { }
files {
"**.cpp",
"**.h"
}
if os.is("Windows") then
links {"winmm"}
defines {"__WINDOWS_MM__", "WIN32"}
end
if os.is("Linux") then
defines {"__LINUX_ALSA__"}
links {"asound","pthread"}
end
if os.is("MacOSX") then
links{"CoreAudio.framework", "coreMIDI.framework", "Cocoa.framework"}
defines {"__MACOSX_CORE__"}
end

View File

@@ -13,7 +13,13 @@
// vrtypes.h
#ifndef _INCLUDE_VRTYPES_H
#define _INCLUDE_VRTYPES_H
#define _INCLUDE_VRTYPES_H
// Forward declarations to avoid requiring vulkan.h
struct VkDevice_T;
struct VkPhysicalDevice_T;
struct VkInstance_T;
struct VkQueue_T;
namespace vr
{
@@ -125,6 +131,10 @@ struct Texture_t
EColorSpace eColorSpace;
};
// Handle to a shared texture (HANDLE on Windows obtained using OpenSharedResource).
typedef uint64_t SharedTextureHandle_t;
#define INVALID_SHARED_TEXTURE_HANDLE ((vr::SharedTextureHandle_t)0)
enum ETrackingResult
{
TrackingResult_Uninitialized = 1,
@@ -154,6 +164,8 @@ enum ETrackedDeviceClass
TrackedDeviceClass_Controller = 2, // Tracked controllers
TrackedDeviceClass_TrackingReference = 4, // Camera and base stations that serve as tracking reference points
TrackedDeviceClass_Count, // This isn't a class that will ever be returned. It is used for allocating arrays and such
TrackedDeviceClass_Other = 1000,
};
@@ -277,6 +289,7 @@ enum ETrackedDeviceProperty
Prop_Axis2Type_Int32 = 3004, // Return value is of type EVRControllerAxisType
Prop_Axis3Type_Int32 = 3005, // Return value is of type EVRControllerAxisType
Prop_Axis4Type_Int32 = 3006, // Return value is of type EVRControllerAxisType
Prop_ControllerRoleHint_Int32 = 3007, // Return value is of type ETrackedControllerRole
// Properties that are unique to TrackedDeviceClass_TrackingReference
Prop_FieldOfViewLeftDegrees_Float = 4000,
@@ -287,6 +300,17 @@ enum ETrackedDeviceProperty
Prop_TrackingRangeMaximumMeters_Float = 4005,
Prop_ModeLabel_String = 4006,
// Properties that are used for user interface like icons names
Prop_IconPathName_String = 5000, // usually a directory named "icons"
Prop_NamedIconPathDeviceOff_String = 5001, // PNG for static icon, or GIF for animation, 50x32 for headsets and 32x32 for others
Prop_NamedIconPathDeviceSearching_String = 5002, // PNG for static icon, or GIF for animation, 50x32 for headsets and 32x32 for others
Prop_NamedIconPathDeviceSearchingAlert_String = 5003, // PNG for static icon, or GIF for animation, 50x32 for headsets and 32x32 for others
Prop_NamedIconPathDeviceReady_String = 5004, // PNG for static icon, or GIF for animation, 50x32 for headsets and 32x32 for others
Prop_NamedIconPathDeviceReadyAlert_String = 5005, // PNG for static icon, or GIF for animation, 50x32 for headsets and 32x32 for others
Prop_NamedIconPathDeviceNotReady_String = 5006, // PNG for static icon, or GIF for animation, 50x32 for headsets and 32x32 for others
Prop_NamedIconPathDeviceStandby_String = 5007, // PNG for static icon, or GIF for animation, 50x32 for headsets and 32x32 for others
Prop_NamedIconPathDeviceAlertLow_String = 5008, // PNG for static icon, or GIF for animation, 50x32 for headsets and 32x32 for others
// Vendors are free to expose private debug data in this reserved region
Prop_VendorSpecific_Reserved_Start = 10000,
Prop_VendorSpecific_Reserved_End = 10999,
@@ -332,6 +356,22 @@ enum EVRSubmitFlags
// If the texture pointer passed in is actually a renderbuffer (e.g. for MSAA in OpenGL) then set this flag.
Submit_GlRenderBuffer = 0x02,
// Handle is pointer to VulkanData_t
Submit_VulkanTexture = 0x04,
};
/** Data required for passing Vulkan textures to IVRCompositor::Submit.
* Be sure to call OpenVR_Shutdown before destroying these resources. */
struct VulkanData_t
{
uint64_t m_nImage; // VkImage
VkDevice_T *m_pDevice;
VkPhysicalDevice_T *m_pPhysicalDevice;
VkInstance_T *m_pInstance;
VkQueue_T *m_pQueue;
uint32_t m_nQueueFamilyIndex;
uint32_t m_nWidth, m_nHeight, m_nFormat, m_nSampleCount;
};
@@ -346,6 +386,7 @@ enum EVRState
VRState_Ready_Alert = 4,
VRState_NotReady = 5,
VRState_Standby = 6,
VRState_Ready_Alert_Low = 7,
};
/** The types of events that could be posted (and what the parameters mean for each event type) */
@@ -362,6 +403,8 @@ enum EVREventType
VREvent_EnterStandbyMode = 106,
VREvent_LeaveStandbyMode = 107,
VREvent_TrackedDeviceRoleChanged = 108,
VREvent_WatchdogWakeUpRequested = 109,
VREvent_LensDistortionChanged = 110,
VREvent_ButtonPress = 200, // data is controller
VREvent_ButtonUnpress = 201, // data is controller
@@ -375,6 +418,7 @@ enum EVREventType
VREvent_FocusLeave = 304, // data is overlay
VREvent_Scroll = 305, // data is mouse
VREvent_TouchPadMove = 306, // data is mouse
VREvent_OverlayFocusChanged = 307, // data is overlay, global event
VREvent_InputFocusCaptured = 400, // data is process DEPRECATED
VREvent_InputFocusReleased = 401, // data is process DEPRECATED
@@ -406,12 +450,14 @@ enum EVREventType
VREvent_DashboardGuideButtonUp = 515,
VREvent_ScreenshotTriggered = 516, // Screenshot button combo was pressed, Dashboard should request a screenshot
VREvent_ImageFailed = 517, // Sent to overlays when a SetOverlayRaw or SetOverlayfromFail fails to load
VREvent_DashboardOverlayCreated = 518,
// Screenshot API
VREvent_RequestScreenshot = 520, // Sent by vrclient application to compositor to take a screenshot
VREvent_ScreenshotTaken = 521, // Sent by compositor to the application that the screenshot has been taken
VREvent_ScreenshotFailed = 522, // Sent by compositor to the application that the screenshot failed to be taken
VREvent_SubmitScreenshotToDashboard = 523, // Sent by compositor to the dashboard that a completed screenshot was submitted
VREvent_ScreenshotProgressToDashboard = 524, // Sent by compositor to the dashboard that a completed screenshot was submitted
VREvent_Notification_Shown = 600,
VREvent_Notification_Hidden = 601,
@@ -437,6 +483,7 @@ enum EVREventType
VREvent_ReprojectionSettingHasChanged = 852,
VREvent_ModelSkinSettingsHaveChanged = 853,
VREvent_EnvironmentSettingsHaveChanged = 854,
VREvent_PowerSettingsHaveChanged = 855,
VREvent_StatusUpdate = 900,
@@ -453,6 +500,7 @@ enum EVREventType
VREvent_ApplicationTransitionAborted = 1301,
VREvent_ApplicationTransitionNewAppStarted = 1302,
VREvent_ApplicationListUpdated = 1303,
VREvent_ApplicationMimeTypeLoad = 1304,
VREvent_Compositor_MirrorWindowShown = 1400,
VREvent_Compositor_MirrorWindowHidden = 1401,
@@ -463,6 +511,7 @@ enum EVREventType
VREvent_TrackedCamera_StopVideoStream = 1501,
VREvent_TrackedCamera_PauseVideoStream = 1502,
VREvent_TrackedCamera_ResumeVideoStream = 1503,
VREvent_TrackedCamera_EditingSurface = 1550,
VREvent_PerformanceTest_EnableCapture = 1600,
VREvent_PerformanceTest_DisableCapture = 1601,
@@ -496,6 +545,8 @@ enum EVRButtonId
k_EButton_DPad_Right = 5,
k_EButton_DPad_Down = 6,
k_EButton_A = 7,
k_EButton_ProximitySensor = 31,
k_EButton_Axis0 = 32,
k_EButton_Axis1 = 33,
@@ -634,6 +685,23 @@ struct VREvent_Screenshot_t
uint32_t type;
};
struct VREvent_ScreenshotProgress_t
{
float progress;
};
struct VREvent_ApplicationLaunch_t
{
uint32_t pid;
uint32_t unArgsHandle;
};
struct VREvent_EditingCameraSurface_t
{
uint64_t overlayHandle;
uint32_t nVisualMode;
};
/** If you change this you must manually update openvr_interop.cs.py */
typedef union
{
@@ -652,6 +720,9 @@ typedef union
VREvent_TouchPadMove_t touchPadMove;
VREvent_SeatedZeroPoseReset_t seatedZeroPoseReset;
VREvent_Screenshot_t screenshot;
VREvent_ScreenshotProgress_t screenshotProgress;
VREvent_ApplicationLaunch_t applicationLaunch;
VREvent_EditingCameraSurface_t cameraSurface;
} VREvent_Data_t;
/** An event posted by the server to all running applications */
@@ -779,7 +850,7 @@ enum EVROverlayError
VROverlayError_RequestFailed = 23,
VROverlayError_InvalidTexture = 24,
VROverlayError_UnableToLoadFile = 25,
VROVerlayError_KeyboardAlreadyInUse = 26,
VROverlayError_KeyboardAlreadyInUse = 26,
VROverlayError_NoNeighbor = 27,
};
@@ -795,6 +866,9 @@ enum EVRApplicationType
VRApplication_Utility = 4, // Init should not try to load any drivers. The application needs access to utility
// interfaces (like IVRSettings and IVRApplications) but not hardware.
VRApplication_VRMonitor = 5, // Reserved for vrmonitor
VRApplication_SteamWatchdog = 6,// Reserved for Steam
VRApplication_Max
};
@@ -851,6 +925,14 @@ enum EVRInitError
VRInitError_Init_NotSupportedWithCompositor = 122,
VRInitError_Init_NotAvailableToUtilityApps = 123,
VRInitError_Init_Internal = 124,
VRInitError_Init_HmdDriverIdIsNone = 125,
VRInitError_Init_HmdNotFoundPresenceFailed = 126,
VRInitError_Init_VRMonitorNotFound = 127,
VRInitError_Init_VRMonitorStartupFailed = 128,
VRInitError_Init_LowPowerWatchdogNotSupported = 129,
VRInitError_Init_InvalidApplicationType = 130,
VRInitError_Init_NotAvailableToWatchdogApps = 131,
VRInitError_Init_WatchdogDisabledInSettings = 132,
VRInitError_Driver_Failed = 200,
VRInitError_Driver_Unknown = 201,
@@ -861,13 +943,20 @@ enum EVRInitError
VRInitError_Driver_NotCalibrated = 206,
VRInitError_Driver_CalibrationInvalid = 207,
VRInitError_Driver_HmdDisplayNotFound = 208,
VRInitError_Driver_TrackedDeviceInterfaceUnknown = 209,
// VRInitError_Driver_HmdDisplayNotFoundAfterFix = 210, // not needed: here for historic reasons
VRInitError_Driver_HmdDriverIdOutOfBounds = 211,
VRInitError_Driver_HmdDisplayMirrored = 212,
VRInitError_IPC_ServerInitFailed = 300,
VRInitError_IPC_ConnectFailed = 301,
VRInitError_IPC_SharedStateInitFailed = 302,
VRInitError_IPC_CompositorInitFailed = 303,
VRInitError_IPC_MutexInitFailed = 304,
VRInitError_IPC_Failed = 305,
VRInitError_IPC_CompositorConnectFailed = 306,
VRInitError_IPC_CompositorInvalidConnectResponse = 307,
VRInitError_IPC_ConnectFailedAfterMultipleAttempts = 308,
VRInitError_Compositor_Failed = 400,
VRInitError_Compositor_D3D11HardwareRequired = 401,
@@ -971,7 +1060,7 @@ static const uint32_t k_unScreenshotHandleInvalid = 0;
#define VR_INTERFACE extern "C" __declspec( dllimport )
#endif
#elif defined(GNUC) || defined(COMPILER_GCC) || defined(__APPLE__)
#elif defined(__GNUC__) || defined(COMPILER_GCC) || defined(__APPLE__)
#ifdef VR_API_EXPORT
#define VR_INTERFACE extern "C" __attribute__((visibility("default")))
@@ -1038,7 +1127,8 @@ public:
virtual void GetProjectionRaw( EVREye eEye, float *pfLeft, float *pfRight, float *pfTop, float *pfBottom ) = 0;
/** Returns the result of the distortion function for the specified eye and input UVs. UVs go from 0,0 in
* the upper left of that eye's viewport and 1,1 in the lower right of that eye's viewport. */
* the upper left of that eye's viewport and 1,1 in the lower right of that eye's viewport.
* Values may be NAN to indicate an error has occurred. */
virtual DistortionCoordinates_t ComputeDistortion( EVREye eEye, float fU, float fV ) = 0;
/** Returns the transform from eye space to the head space. Eye space is the per-eye flavor of head
@@ -1060,8 +1150,10 @@ public:
virtual int32_t GetD3D9AdapterIndex() = 0;
/** [D3D10/11 Only]
* Returns the adapter index and output index that the user should pass into EnumAdapters and EnumOutputs
* to create the device and swap chain in DX10 and DX11. If an error occurs both indices will be set to -1.
* Returns the adapter index that the user should pass into EnumAdapters to create the device
* and swap chain in DX10 and DX11. If an error occurs the index will be set to -1. The index will
* also be -1 if the headset is in direct mode on the driver side instead of using the compositor's
* builtin direct mode support.
*/
virtual void GetDXGIOutputInfo( int32_t *pnAdapterIndex ) = 0;
@@ -1361,6 +1453,10 @@ namespace vr
const char *pchValue;
};
/** Currently recognized mime types */
static const char * const k_pch_MimeType_HomeApp = "vr/home";
static const char * const k_pch_MimeType_GameTheater = "vr/game_theater";
class IVRApplications
{
public:
@@ -1383,7 +1479,7 @@ namespace vr
/** Returns the key of the specified application. The index is at least 0 and is less than the return
* value of GetApplicationCount(). The buffer should be at least k_unMaxApplicationKeyLength in order to
* fit the key. */
virtual EVRApplicationError GetApplicationKeyByIndex( uint32_t unApplicationIndex, char *pchAppKeyBuffer, uint32_t unAppKeyBufferLen ) = 0;
virtual EVRApplicationError GetApplicationKeyByIndex( uint32_t unApplicationIndex, VR_OUT_STRING() char *pchAppKeyBuffer, uint32_t unAppKeyBufferLen ) = 0;
/** Returns the key of the application for the specified Process Id. The buffer should be at least
* k_unMaxApplicationKeyLength in order to fit the key. */
@@ -1398,6 +1494,9 @@ namespace vr
*/
virtual EVRApplicationError LaunchTemplateApplication( const char *pchTemplateAppKey, const char *pchNewAppKey, VR_ARRAY_COUNT( unKeys ) const AppOverrideKeys_t *pKeys, uint32_t unKeys ) = 0;
/** launches the application currently associated with this mime type and passes it the option args, typically the filename or object name of the item being launched */
virtual vr::EVRApplicationError LaunchApplicationFromMimeType( const char *pchMimeType, const char *pchArgs ) = 0;
/** Launches the dashboard overlay application if it is not already running. This call is only valid for
* dashboard overlay applications. */
virtual EVRApplicationError LaunchDashboardOverlay( const char *pchAppKey ) = 0;
@@ -1420,7 +1519,7 @@ namespace vr
// --------------- Application properties --------------- //
/** Returns a value for an application property. The required buffer size to fit this value will be returned. */
virtual uint32_t GetApplicationPropertyString( const char *pchAppKey, EVRApplicationProperty eProperty, char *pchPropertyValueBuffer, uint32_t unPropertyValueBufferLen, EVRApplicationError *peError = nullptr ) = 0;
virtual uint32_t GetApplicationPropertyString( const char *pchAppKey, EVRApplicationProperty eProperty, VR_OUT_STRING() char *pchPropertyValueBuffer, uint32_t unPropertyValueBufferLen, EVRApplicationError *peError = nullptr ) = 0;
/** Returns a bool value for an application property. Returns false in all error cases. */
virtual bool GetApplicationPropertyBool( const char *pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError *peError = nullptr ) = 0;
@@ -1434,6 +1533,21 @@ namespace vr
/** Gets the application auto-launch flag. This is only valid for applications which return true for VRApplicationProperty_IsDashboardOverlay_Bool. */
virtual bool GetApplicationAutoLaunch( const char *pchAppKey ) = 0;
/** Adds this mime-type to the list of supported mime types for this application*/
virtual EVRApplicationError SetDefaultApplicationForMimeType( const char *pchAppKey, const char *pchMimeType ) = 0;
/** return the app key that will open this mime type */
virtual bool GetDefaultApplicationForMimeType( const char *pchMimeType, char *pchAppKeyBuffer, uint32_t unAppKeyBufferLen ) = 0;
/** Get the list of supported mime types for this application, comma-delimited */
virtual bool GetApplicationSupportedMimeTypes( const char *pchAppKey, char *pchMimeTypesBuffer, uint32_t unMimeTypesBuffer ) = 0;
/** Get the list of app-keys that support this mime type, comma-delimited, the return value is number of bytes you need to return the full string */
virtual uint32_t GetApplicationsThatSupportMimeType( const char *pchMimeType, char *pchAppKeysThatSupportBuffer, uint32_t unAppKeysThatSupportBuffer ) = 0;
/** Get the args list from an app launch that had the process already running, you call this when you get a VREvent_ApplicationMimeTypeLoad */
virtual uint32_t GetApplicationLaunchArguments( uint32_t unHandle, char *pchArgs, uint32_t unArgs ) = 0;
// --------------- Transition methods --------------- //
/** Returns the app key for the application that is starting up */
@@ -1467,7 +1581,7 @@ namespace vr
virtual EVRApplicationError LaunchInternalProcess( const char *pchBinaryPath, const char *pchArguments, const char *pchWorkingDirectory ) = 0;
};
static const char * const IVRApplications_Version = "IVRApplications_005";
static const char * const IVRApplications_Version = "IVRApplications_006";
} // namespace vr
@@ -1480,6 +1594,8 @@ namespace vr
VRSettingsError_IPCFailed = 1,
VRSettingsError_WriteFailed = 2,
VRSettingsError_ReadFailed = 3,
VRSettingsError_JsonParseFailed = 4,
VRSettingsError_UnsetSettingHasNoDefault = 5, // This will be returned if the setting does not appear in the appropriate default file and has not been set
};
// The maximum length of a settings key
@@ -1493,21 +1609,24 @@ namespace vr
// Returns true if file sync occurred (force or settings dirty)
virtual bool Sync( bool bForce = false, EVRSettingsError *peError = nullptr ) = 0;
virtual bool GetBool( const char *pchSection, const char *pchSettingsKey, bool bDefaultValue, EVRSettingsError *peError = nullptr ) = 0;
virtual void SetBool( const char *pchSection, const char *pchSettingsKey, bool bValue, EVRSettingsError *peError = nullptr ) = 0;
virtual int32_t GetInt32( const char *pchSection, const char *pchSettingsKey, int32_t nDefaultValue, EVRSettingsError *peError = nullptr ) = 0;
virtual void SetInt32( const char *pchSection, const char *pchSettingsKey, int32_t nValue, EVRSettingsError *peError = nullptr ) = 0;
virtual float GetFloat( const char *pchSection, const char *pchSettingsKey, float flDefaultValue, EVRSettingsError *peError = nullptr ) = 0;
virtual void SetFloat( const char *pchSection, const char *pchSettingsKey, float flValue, EVRSettingsError *peError = nullptr ) = 0;
virtual void GetString( const char *pchSection, const char *pchSettingsKey, char *pchValue, uint32_t unValueLen, const char *pchDefaultValue, EVRSettingsError *peError = nullptr ) = 0;
virtual void SetString( const char *pchSection, const char *pchSettingsKey, const char *pchValue, EVRSettingsError *peError = nullptr ) = 0;
// Users of the system need to provide a proper default in default.vrsettings in the resources/settings/ directory
// of either the runtime or the driver_xxx directory. Otherwise the default will be false, 0, 0.0 or ""
virtual bool GetBool( const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr ) = 0;
virtual int32_t GetInt32( const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr ) = 0;
virtual float GetFloat( const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr ) = 0;
virtual void GetString( const char *pchSection, const char *pchSettingsKey, VR_OUT_STRING() char *pchValue, uint32_t unValueLen, EVRSettingsError *peError = nullptr ) = 0;
virtual void RemoveSection( const char *pchSection, EVRSettingsError *peError = nullptr ) = 0;
virtual void RemoveKeyInSection( const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr ) = 0;
};
//-----------------------------------------------------------------------------
static const char * const IVRSettings_Version = "IVRSettings_001";
static const char * const IVRSettings_Version = "IVRSettings_002";
//-----------------------------------------------------------------------------
// steamvr keys
@@ -1532,9 +1651,6 @@ namespace vr
static const char * const k_pch_SteamVR_PlayAreaColor_String = "playAreaColor";
static const char * const k_pch_SteamVR_ShowStage_Bool = "showStage";
static const char * const k_pch_SteamVR_ActivateMultipleDrivers_Bool = "activateMultipleDrivers";
static const char * const k_pch_SteamVR_PowerOffOnExit_Bool = "powerOffOnExit";
static const char * const k_pch_SteamVR_StandbyAppRunningTimeout_Float = "standbyAppRunningTimeout";
static const char * const k_pch_SteamVR_StandbyNoAppTimeout_Float = "standbyNoAppTimeout";
static const char * const k_pch_SteamVR_DirectMode_Bool = "directMode";
static const char * const k_pch_SteamVR_DirectModeEdidVid_Int32 = "directModeEdidVid";
static const char * const k_pch_SteamVR_DirectModeEdidPid_Int32 = "directModeEdidPid";
@@ -1548,6 +1664,13 @@ namespace vr
static const char * const k_pch_SteamVR_ForceFadeOnBadTracking_Bool = "forceFadeOnBadTracking";
static const char * const k_pch_SteamVR_DefaultMirrorView_Int32 = "defaultMirrorView";
static const char * const k_pch_SteamVR_ShowMirrorView_Bool = "showMirrorView";
static const char * const k_pch_SteamVR_MirrorViewGeometry_String = "mirrorViewGeometry";
static const char * const k_pch_SteamVR_StartMonitorFromAppLaunch = "startMonitorFromAppLaunch";
static const char * const k_pch_SteamVR_EnableHomeApp = "enableHomeApp";
static const char * const k_pch_SteamVR_SetInitialDefaultHomeApp = "setInitialDefaultHomeApp";
static const char * const k_pch_SteamVR_CycleBackgroundImageTimeSec_Int32 = "CycleBackgroundImageTimeSec";
static const char * const k_pch_SteamVR_RetailDemo_Bool = "retailDemo";
//-----------------------------------------------------------------------------
// lighthouse keys
@@ -1558,9 +1681,6 @@ namespace vr
static const char * const k_pch_Lighthouse_DisambiguationDebug_Int32 = "disambiguationdebug";
static const char * const k_pch_Lighthouse_PrimaryBasestation_Int32 = "primarybasestation";
static const char * const k_pch_Lighthouse_LighthouseName_String = "lighthousename";
static const char * const k_pch_Lighthouse_MaxIncidenceAngleDegrees_Float = "maxincidenceangledegrees";
static const char * const k_pch_Lighthouse_UseLighthouseDirect_Bool = "uselighthousedirect";
static const char * const k_pch_Lighthouse_DBHistory_Bool = "dbhistory";
//-----------------------------------------------------------------------------
@@ -1583,7 +1703,8 @@ namespace vr
// user interface keys
static const char * const k_pch_UserInterface_Section = "userinterface";
static const char * const k_pch_UserInterface_StatusAlwaysOnTop_Bool = "StatusAlwaysOnTop";
static const char * const k_pch_UserInterface_EnableScreenshots_Bool = "EnableScreenshots";
static const char * const k_pch_UserInterface_Screenshots_Bool = "screenshots";
static const char * const k_pch_UserInterface_ScreenshotType_Int = "screenshotType";
//-----------------------------------------------------------------------------
// notification keys
@@ -1635,6 +1756,7 @@ namespace vr
static const char * const k_pch_Camera_BoundsColorGammaG_Int32 = "cameraBoundsColorGammaG";
static const char * const k_pch_Camera_BoundsColorGammaB_Int32 = "cameraBoundsColorGammaB";
static const char * const k_pch_Camera_BoundsColorGammaA_Int32 = "cameraBoundsColorGammaA";
static const char * const k_pch_Camera_BoundsStrength_Int32 = "cameraBoundsStrength";
//-----------------------------------------------------------------------------
// audio keys
@@ -1646,6 +1768,21 @@ namespace vr
static const char * const k_pch_audio_OffRecordDevice_String = "offRecordDevice";
static const char * const k_pch_audio_VIVEHDMIGain = "viveHDMIGain";
//-----------------------------------------------------------------------------
// power management keys
static const char * const k_pch_Power_Section = "power";
static const char * const k_pch_Power_PowerOffOnExit_Bool = "powerOffOnExit";
static const char * const k_pch_Power_TurnOffScreensTimeout_Float = "turnOffScreensTimeout";
static const char * const k_pch_Power_TurnOffControllersTimeout_Float = "turnOffControllersTimeout";
static const char * const k_pch_Power_ReturnToWatchdogTimeout_Float = "returnToWatchdogTimeout";
static const char * const k_pch_Power_AutoLaunchSteamVROnButtonPress = "autoLaunchSteamVROnButtonPress";
//-----------------------------------------------------------------------------
// dashboard keys
static const char * const k_pch_Dashboard_Section = "dashboard";
static const char * const k_pch_Dashboard_EnableDashboard_Bool = "enableDashboard";
static const char * const k_pch_Dashboard_ArcadeMode_Bool = "arcadeMode";
//-----------------------------------------------------------------------------
// model skin keys
static const char * const k_pch_modelskin_Section = "modelskins";
@@ -1862,6 +1999,7 @@ struct Compositor_FrameTiming
uint32_t m_nFrameIndex;
uint32_t m_nNumFramePresents; // number of times this frame was presented
uint32_t m_nNumDroppedFrames; // number of additional times previous frame was scanned out
uint32_t m_nReprojectionFlags;
/** Absolute time reference for comparing frames. This aligns with the vsync that running start is relative to. */
double m_flSystemTimeInSeconds;
@@ -1870,7 +2008,8 @@ struct Compositor_FrameTiming
* The fewer packets of work these are broken up into, the less likely this will happen.
* GPU work can be broken up by calling Flush. This can sometimes be useful to get the GPU started
* processing that work earlier in the frame. */
float m_flSceneRenderGpuMs; // time spent rendering the scene
float m_flPreSubmitGpuMs; // time spent rendering the scene (gpu work submitted between WaitGetPoses and second Submit)
float m_flPostSubmitGpuMs; // additional time spent rendering by application (e.g. companion window)
float m_flTotalRenderGpuMs; // time between work submitted immediately after present (ideally vsync) until the end of compositor submitted work
float m_flCompositorRenderGpuMs; // time spend performing distortion correction, rendering chaperone, overlays, etc.
float m_flCompositorRenderCpuMs; // time spent on cpu submitting the above work for this frame
@@ -1891,9 +2030,6 @@ struct Compositor_FrameTiming
float m_flCompositorRenderStartMs;
vr::TrackedDevicePose_t m_HmdPose; // pose used by app to render this frame
int32_t m_nFidelityLevel; // app reported value
uint32_t m_nReprojectionFlags;
};
/** Cumulative stats for current application. These are not cleared until a new app connects,
@@ -1903,7 +2039,7 @@ struct Compositor_CumulativeStats
uint32_t m_nPid; // Process id associated with these stats (may no longer be running).
uint32_t m_nNumFramePresents; // total number of times we called present (includes reprojected frames)
uint32_t m_nNumDroppedFrames; // total number of times an old frame was re-scanned out (without reprojection)
uint32_t m_nNumReprojectedFrames; // total number of times a frame was scanned out a second time with reprojection
uint32_t m_nNumReprojectedFrames; // total number of times a frame was scanned out a second time (with reprojection)
/** Values recorded at startup before application has fully faded in the first time. */
uint32_t m_nNumFramePresentsOnStartup;
@@ -2045,14 +2181,6 @@ public:
/** Temporarily suspends rendering (useful for finer control over scene transitions). */
virtual void SuspendRendering( bool bSuspend ) = 0;
/** Screenshot support */
/** These functions are no longer used and will be removed in
* a future update. Use the functions via the
* IVRScreenshots interface */
virtual vr::EVRCompositorError RequestScreenshot( vr::EVRScreenshotType type, const char *pchDestinationFileName, const char *pchVRDestinationFileName ) = 0;
virtual vr::EVRScreenshotType GetCurrentScreenshotType() = 0;
/** Opens a shared D3D11 texture with the undistorted composited image for each eye. */
virtual vr::EVRCompositorError GetMirrorTextureD3D11( vr::EVREye eEye, void *pD3D11DeviceOrResource, void **ppD3D11ShaderResourceView ) = 0;
@@ -2063,7 +2191,7 @@ public:
virtual void UnlockGLSharedTextureForAccess( vr::glSharedTextureHandle_t glSharedTextureHandle ) = 0;
};
static const char * const IVRCompositor_Version = "IVRCompositor_015";
static const char * const IVRCompositor_Version = "IVRCompositor_016";
} // namespace vr
@@ -2178,7 +2306,7 @@ namespace vr
static const uint32_t k_unVROverlayMaxNameLength = 128;
/** The maximum number of overlays that can exist in the system at one time. */
static const uint32_t k_unMaxOverlayCount = 32;
static const uint32_t k_unMaxOverlayCount = 64;
/** Types of input supported by VR Overlays */
enum VROverlayInputMethod
@@ -2232,6 +2360,10 @@ namespace vr
VROverlayFlags_Panorama = 12, // Texture is a panorama
VROverlayFlags_StereoPanorama = 13, // Texture is a stereo panorama
// If this is set on an overlay owned by the scene application that overlay
// will be sorted with the "Other" overlays on top of all other scene overlays
VROverlayFlags_SortWithNonSceneOverlays = 14,
};
struct VROverlayIntersectionParams_t
@@ -2350,6 +2482,26 @@ namespace vr
/** Gets the alpha of the overlay quad. By default overlays are rendering at 100 percent alpha (1.0). */
virtual EVROverlayError GetOverlayAlpha( VROverlayHandle_t ulOverlayHandle, float *pfAlpha ) = 0;
/** Sets the aspect ratio of the texels in the overlay. 1.0 means the texels are square. 2.0 means the texels
* are twice as wide as they are tall. Defaults to 1.0. */
virtual EVROverlayError SetOverlayTexelAspect( VROverlayHandle_t ulOverlayHandle, float fTexelAspect ) = 0;
/** Gets the aspect ratio of the texels in the overlay. Defaults to 1.0 */
virtual EVROverlayError GetOverlayTexelAspect( VROverlayHandle_t ulOverlayHandle, float *pfTexelAspect ) = 0;
/** Sets the rendering sort order for the overlay. Overlays are rendered this order:
* Overlays owned by the scene application
* Overlays owned by some other application
*
* Within a category overlays are rendered lowest sort order to highest sort order. Overlays with the same
* sort order are rendered back to front base on distance from the HMD.
*
* Sort order defaults to 0. */
virtual EVROverlayError SetOverlaySortOrder( VROverlayHandle_t ulOverlayHandle, uint32_t unSortOrder ) = 0;
/** Gets the sort order of the overlay. See SetOverlaySortOrder for how this works. */
virtual EVROverlayError GetOverlaySortOrder( VROverlayHandle_t ulOverlayHandle, uint32_t *punSortOrder ) = 0;
/** Sets the width of the overlay quad in meters. By default overlays are rendered on a quad that is 1 meter across */
virtual EVROverlayError SetOverlayWidthInMeters( VROverlayHandle_t ulOverlayHandle, float fWidthInMeters ) = 0;
@@ -2553,7 +2705,7 @@ namespace vr
};
static const char * const IVROverlay_Version = "IVROverlay_012";
static const char * const IVROverlay_Version = "IVROverlay_013";
} // namespace vr
@@ -2758,7 +2910,7 @@ namespace vr
{
/** NOTE: Use of this interface is not recommended in production applications. It will not work for displays which use
* direct-to-display mode. It is also incompatible with the VR compositor and is not available when the compositor is running. */
* direct-to-display mode. Creating our own window is also incompatible with the VR compositor and is not available when the compositor is running. */
class IVRExtendedDisplay
{
public:
@@ -2815,6 +2967,16 @@ public:
* If there is no frame available yet, due to initial camera spinup or re-activation, the error will be VRTrackedCameraError_NoFrameAvailable.
* Ideally a caller should be polling at ~16ms intervals */
virtual vr::EVRTrackedCameraError GetVideoStreamFrameBuffer( vr::TrackedCameraHandle_t hTrackedCamera, vr::EVRTrackedCameraFrameType eFrameType, void *pFrameBuffer, uint32_t nFrameBufferSize, vr::CameraVideoStreamFrameHeader_t *pFrameHeader, uint32_t nFrameHeaderSize ) = 0;
/** Gets size of the image frame. */
virtual vr::EVRTrackedCameraError GetVideoStreamTextureSize( vr::TrackedDeviceIndex_t nDeviceIndex, vr::EVRTrackedCameraFrameType eFrameType, vr::VRTextureBounds_t *pTextureBounds, uint32_t *pnWidth, uint32_t *pnHeight ) = 0;
/** Access a shared D3D11 texture for the specified tracked camera stream */
virtual vr::EVRTrackedCameraError GetVideoStreamTextureD3D11( vr::TrackedCameraHandle_t hTrackedCamera, vr::EVRTrackedCameraFrameType eFrameType, void *pD3D11DeviceOrResource, void **ppD3D11ShaderResourceView, vr::CameraVideoStreamFrameHeader_t *pFrameHeader, uint32_t nFrameHeaderSize ) = 0;
/** Access a shared GL texture for the specified tracked camera stream */
virtual vr::EVRTrackedCameraError GetVideoStreamTextureGL( vr::TrackedCameraHandle_t hTrackedCamera, vr::EVRTrackedCameraFrameType eFrameType, vr::glUInt_t *pglTextureId, vr::CameraVideoStreamFrameHeader_t *pFrameHeader, uint32_t nFrameHeaderSize ) = 0;
virtual vr::EVRTrackedCameraError ReleaseVideoStreamTextureGL( vr::TrackedCameraHandle_t hTrackedCamera, vr::glUInt_t glTextureId ) = 0;
};
static const char * const IVRTrackedCamera_Version = "IVRTrackedCamera_003";
@@ -2929,7 +3091,33 @@ static const char * const IVRScreenshots_Version = "IVRScreenshots_001";
} // namespace vr
// End
// ivrresources.h
namespace vr
{
class IVRResources
{
public:
// ------------------------------------
// Shared Resource Methods
// ------------------------------------
/** Loads the specified resource into the provided buffer if large enough.
* Returns the size in bytes of the buffer required to hold the specified resource. */
virtual uint32_t LoadSharedResource( const char *pchResourceName, char *pchBuffer, uint32_t unBufferLen ) = 0;
/** Provides the full path to the specified resource. Resource names can include named directories for
* drivers and other things, and this resolves all of those and returns the actual physical path.
* pchResourceTypeDirectory is the subdirectory of resources to look in. */
virtual uint32_t GetResourceFullPath( const char *pchResourceName, const char *pchResourceTypeDirectory, char *pchPathBuffer, uint32_t unBufferLen ) = 0;
};
static const char * const IVRResources_Version = "IVRResources_001";
}// End
#endif // _OPENVR_API
@@ -3074,6 +3262,17 @@ namespace vr
return m_pVROverlay;
}
IVRResources *VRResources()
{
CheckClear();
if ( m_pVRResources == nullptr )
{
EVRInitError eError;
m_pVRResources = (IVRResources *)VR_GetGenericInterface( IVRResources_Version, &eError );
}
return m_pVRResources;
}
IVRScreenshots *VRScreenshots()
{
CheckClear();
@@ -3146,6 +3345,7 @@ namespace vr
IVRChaperoneSetup *m_pVRChaperoneSetup;
IVRCompositor *m_pVRCompositor;
IVROverlay *m_pVROverlay;
IVRResources *m_pVRResources;
IVRRenderModels *m_pVRRenderModels;
IVRExtendedDisplay *m_pVRExtendedDisplay;
IVRSettings *m_pVRSettings;
@@ -3169,6 +3369,7 @@ namespace vr
inline IVRRenderModels *VR_CALLTYPE VRRenderModels() { return OpenVRInternal_ModuleContext().VRRenderModels(); }
inline IVRApplications *VR_CALLTYPE VRApplications() { return OpenVRInternal_ModuleContext().VRApplications(); }
inline IVRSettings *VR_CALLTYPE VRSettings() { return OpenVRInternal_ModuleContext().VRSettings(); }
inline IVRResources *VR_CALLTYPE VRResources() { return OpenVRInternal_ModuleContext().VRResources(); }
inline IVRExtendedDisplay *VR_CALLTYPE VRExtendedDisplay() { return OpenVRInternal_ModuleContext().VRExtendedDisplay(); }
inline IVRTrackedCamera *VR_CALLTYPE VRTrackedCamera() { return OpenVRInternal_ModuleContext().VRTrackedCamera(); }
@@ -3184,6 +3385,7 @@ namespace vr
m_pVRSettings = nullptr;
m_pVRApplications = nullptr;
m_pVRTrackedCamera = nullptr;
m_pVRResources = nullptr;
m_pVRScreenshots = nullptr;
}

View File

@@ -300,6 +300,26 @@ public struct IVRTrackedCamera
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetVideoStreamFrameBuffer GetVideoStreamFrameBuffer;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate EVRTrackedCameraError _GetVideoStreamTextureSize(uint nDeviceIndex, EVRTrackedCameraFrameType eFrameType, ref VRTextureBounds_t pTextureBounds, ref uint pnWidth, ref uint pnHeight);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetVideoStreamTextureSize GetVideoStreamTextureSize;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate EVRTrackedCameraError _GetVideoStreamTextureD3D11(ulong hTrackedCamera, EVRTrackedCameraFrameType eFrameType, IntPtr pD3D11DeviceOrResource, ref IntPtr ppD3D11ShaderResourceView, ref CameraVideoStreamFrameHeader_t pFrameHeader, uint nFrameHeaderSize);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetVideoStreamTextureD3D11 GetVideoStreamTextureD3D11;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate EVRTrackedCameraError _GetVideoStreamTextureGL(ulong hTrackedCamera, EVRTrackedCameraFrameType eFrameType, ref uint pglTextureId, ref CameraVideoStreamFrameHeader_t pFrameHeader, uint nFrameHeaderSize);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetVideoStreamTextureGL GetVideoStreamTextureGL;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate EVRTrackedCameraError _ReleaseVideoStreamTextureGL(ulong hTrackedCamera, uint glTextureId);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _ReleaseVideoStreamTextureGL ReleaseVideoStreamTextureGL;
}
[StructLayout(LayoutKind.Sequential)]
@@ -326,7 +346,7 @@ public struct IVRApplications
internal _GetApplicationCount GetApplicationCount;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate EVRApplicationError _GetApplicationKeyByIndex(uint unApplicationIndex, string pchAppKeyBuffer, uint unAppKeyBufferLen);
internal delegate EVRApplicationError _GetApplicationKeyByIndex(uint unApplicationIndex, System.Text.StringBuilder pchAppKeyBuffer, uint unAppKeyBufferLen);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetApplicationKeyByIndex GetApplicationKeyByIndex;
@@ -345,6 +365,11 @@ public struct IVRApplications
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _LaunchTemplateApplication LaunchTemplateApplication;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate EVRApplicationError _LaunchApplicationFromMimeType(string pchMimeType, string pchArgs);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _LaunchApplicationFromMimeType LaunchApplicationFromMimeType;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate EVRApplicationError _LaunchDashboardOverlay(string pchAppKey);
[MarshalAs(UnmanagedType.FunctionPtr)]
@@ -371,7 +396,7 @@ public struct IVRApplications
internal _GetApplicationsErrorNameFromEnum GetApplicationsErrorNameFromEnum;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate uint _GetApplicationPropertyString(string pchAppKey, EVRApplicationProperty eProperty, string pchPropertyValueBuffer, uint unPropertyValueBufferLen, ref EVRApplicationError peError);
internal delegate uint _GetApplicationPropertyString(string pchAppKey, EVRApplicationProperty eProperty, System.Text.StringBuilder pchPropertyValueBuffer, uint unPropertyValueBufferLen, ref EVRApplicationError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetApplicationPropertyString GetApplicationPropertyString;
@@ -395,6 +420,31 @@ public struct IVRApplications
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetApplicationAutoLaunch GetApplicationAutoLaunch;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate EVRApplicationError _SetDefaultApplicationForMimeType(string pchAppKey, string pchMimeType);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _SetDefaultApplicationForMimeType SetDefaultApplicationForMimeType;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate bool _GetDefaultApplicationForMimeType(string pchMimeType, string pchAppKeyBuffer, uint unAppKeyBufferLen);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetDefaultApplicationForMimeType GetDefaultApplicationForMimeType;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate bool _GetApplicationSupportedMimeTypes(string pchAppKey, string pchMimeTypesBuffer, uint unMimeTypesBuffer);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetApplicationSupportedMimeTypes GetApplicationSupportedMimeTypes;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate uint _GetApplicationsThatSupportMimeType(string pchMimeType, string pchAppKeysThatSupportBuffer, uint unAppKeysThatSupportBuffer);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetApplicationsThatSupportMimeType GetApplicationsThatSupportMimeType;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate uint _GetApplicationLaunchArguments(uint unHandle, string pchArgs, uint unArgs);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetApplicationLaunchArguments GetApplicationLaunchArguments;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate EVRApplicationError _GetStartingApplication(string pchAppKeyBuffer, uint unAppKeyBufferLen);
[MarshalAs(UnmanagedType.FunctionPtr)]
@@ -730,16 +780,6 @@ public struct IVRCompositor
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _SuspendRendering SuspendRendering;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate EVRCompositorError _RequestScreenshot(EVRScreenshotType type, string pchDestinationFileName, string pchVRDestinationFileName);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _RequestScreenshot RequestScreenshot;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate EVRScreenshotType _GetCurrentScreenshotType();
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetCurrentScreenshotType GetCurrentScreenshotType;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate EVRCompositorError _GetMirrorTextureD3D11(EVREye eEye, IntPtr pD3D11DeviceOrResource, ref IntPtr ppD3D11ShaderResourceView);
[MarshalAs(UnmanagedType.FunctionPtr)]
@@ -855,6 +895,26 @@ public struct IVROverlay
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetOverlayAlpha GetOverlayAlpha;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate EVROverlayError _SetOverlayTexelAspect(ulong ulOverlayHandle, float fTexelAspect);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _SetOverlayTexelAspect SetOverlayTexelAspect;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate EVROverlayError _GetOverlayTexelAspect(ulong ulOverlayHandle, ref float pfTexelAspect);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetOverlayTexelAspect GetOverlayTexelAspect;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate EVROverlayError _SetOverlaySortOrder(ulong ulOverlayHandle, uint unSortOrder);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _SetOverlaySortOrder SetOverlaySortOrder;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate EVROverlayError _GetOverlaySortOrder(ulong ulOverlayHandle, ref uint punSortOrder);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetOverlaySortOrder GetOverlaySortOrder;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate EVROverlayError _SetOverlayWidthInMeters(ulong ulOverlayHandle, float fWidthInMeters);
[MarshalAs(UnmanagedType.FunctionPtr)]
@@ -1235,46 +1295,46 @@ public struct IVRSettings
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _Sync Sync;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate bool _GetBool(string pchSection, string pchSettingsKey, bool bDefaultValue, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetBool GetBool;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate void _SetBool(string pchSection, string pchSettingsKey, bool bValue, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _SetBool SetBool;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate int _GetInt32(string pchSection, string pchSettingsKey, int nDefaultValue, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetInt32 GetInt32;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate void _SetInt32(string pchSection, string pchSettingsKey, int nValue, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _SetInt32 SetInt32;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate float _GetFloat(string pchSection, string pchSettingsKey, float flDefaultValue, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetFloat GetFloat;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate void _SetFloat(string pchSection, string pchSettingsKey, float flValue, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _SetFloat SetFloat;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate void _GetString(string pchSection, string pchSettingsKey, string pchValue, uint unValueLen, string pchDefaultValue, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetString GetString;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate void _SetString(string pchSection, string pchSettingsKey, string pchValue, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _SetString SetString;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate bool _GetBool(string pchSection, string pchSettingsKey, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetBool GetBool;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate int _GetInt32(string pchSection, string pchSettingsKey, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetInt32 GetInt32;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate float _GetFloat(string pchSection, string pchSettingsKey, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetFloat GetFloat;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate void _GetString(string pchSection, string pchSettingsKey, System.Text.StringBuilder pchValue, uint unValueLen, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetString GetString;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate void _RemoveSection(string pchSection, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
@@ -1327,6 +1387,21 @@ public struct IVRScreenshots
}
[StructLayout(LayoutKind.Sequential)]
public struct IVRResources
{
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate uint _LoadSharedResource(string pchResourceName, string pchBuffer, uint unBufferLen);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _LoadSharedResource LoadSharedResource;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate uint _GetResourceFullPath(string pchResourceName, string pchResourceTypeDirectory, string pchPathBuffer, uint unBufferLen);
[MarshalAs(UnmanagedType.FunctionPtr)]
internal _GetResourceFullPath GetResourceFullPath;
}
public class CVRSystem
{
@@ -1641,6 +1716,29 @@ public class CVRTrackedCamera
EVRTrackedCameraError result = FnTable.GetVideoStreamFrameBuffer(hTrackedCamera,eFrameType,pFrameBuffer,nFrameBufferSize,ref pFrameHeader,nFrameHeaderSize);
return result;
}
public EVRTrackedCameraError GetVideoStreamTextureSize(uint nDeviceIndex,EVRTrackedCameraFrameType eFrameType,ref VRTextureBounds_t pTextureBounds,ref uint pnWidth,ref uint pnHeight)
{
pnWidth = 0;
pnHeight = 0;
EVRTrackedCameraError result = FnTable.GetVideoStreamTextureSize(nDeviceIndex,eFrameType,ref pTextureBounds,ref pnWidth,ref pnHeight);
return result;
}
public EVRTrackedCameraError GetVideoStreamTextureD3D11(ulong hTrackedCamera,EVRTrackedCameraFrameType eFrameType,IntPtr pD3D11DeviceOrResource,ref IntPtr ppD3D11ShaderResourceView,ref CameraVideoStreamFrameHeader_t pFrameHeader,uint nFrameHeaderSize)
{
EVRTrackedCameraError result = FnTable.GetVideoStreamTextureD3D11(hTrackedCamera,eFrameType,pD3D11DeviceOrResource,ref ppD3D11ShaderResourceView,ref pFrameHeader,nFrameHeaderSize);
return result;
}
public EVRTrackedCameraError GetVideoStreamTextureGL(ulong hTrackedCamera,EVRTrackedCameraFrameType eFrameType,ref uint pglTextureId,ref CameraVideoStreamFrameHeader_t pFrameHeader,uint nFrameHeaderSize)
{
pglTextureId = 0;
EVRTrackedCameraError result = FnTable.GetVideoStreamTextureGL(hTrackedCamera,eFrameType,ref pglTextureId,ref pFrameHeader,nFrameHeaderSize);
return result;
}
public EVRTrackedCameraError ReleaseVideoStreamTextureGL(ulong hTrackedCamera,uint glTextureId)
{
EVRTrackedCameraError result = FnTable.ReleaseVideoStreamTextureGL(hTrackedCamera,glTextureId);
return result;
}
}
@@ -1671,7 +1769,7 @@ public class CVRApplications
uint result = FnTable.GetApplicationCount();
return result;
}
public EVRApplicationError GetApplicationKeyByIndex(uint unApplicationIndex,string pchAppKeyBuffer,uint unAppKeyBufferLen)
public EVRApplicationError GetApplicationKeyByIndex(uint unApplicationIndex,System.Text.StringBuilder pchAppKeyBuffer,uint unAppKeyBufferLen)
{
EVRApplicationError result = FnTable.GetApplicationKeyByIndex(unApplicationIndex,pchAppKeyBuffer,unAppKeyBufferLen);
return result;
@@ -1691,6 +1789,11 @@ public class CVRApplications
EVRApplicationError result = FnTable.LaunchTemplateApplication(pchTemplateAppKey,pchNewAppKey,pKeys,(uint) pKeys.Length);
return result;
}
public EVRApplicationError LaunchApplicationFromMimeType(string pchMimeType,string pchArgs)
{
EVRApplicationError result = FnTable.LaunchApplicationFromMimeType(pchMimeType,pchArgs);
return result;
}
public EVRApplicationError LaunchDashboardOverlay(string pchAppKey)
{
EVRApplicationError result = FnTable.LaunchDashboardOverlay(pchAppKey);
@@ -1716,7 +1819,7 @@ public class CVRApplications
IntPtr result = FnTable.GetApplicationsErrorNameFromEnum(error);
return Marshal.PtrToStringAnsi(result);
}
public uint GetApplicationPropertyString(string pchAppKey,EVRApplicationProperty eProperty,string pchPropertyValueBuffer,uint unPropertyValueBufferLen,ref EVRApplicationError peError)
public uint GetApplicationPropertyString(string pchAppKey,EVRApplicationProperty eProperty,System.Text.StringBuilder pchPropertyValueBuffer,uint unPropertyValueBufferLen,ref EVRApplicationError peError)
{
uint result = FnTable.GetApplicationPropertyString(pchAppKey,eProperty,pchPropertyValueBuffer,unPropertyValueBufferLen,ref peError);
return result;
@@ -1741,6 +1844,31 @@ public class CVRApplications
bool result = FnTable.GetApplicationAutoLaunch(pchAppKey);
return result;
}
public EVRApplicationError SetDefaultApplicationForMimeType(string pchAppKey,string pchMimeType)
{
EVRApplicationError result = FnTable.SetDefaultApplicationForMimeType(pchAppKey,pchMimeType);
return result;
}
public bool GetDefaultApplicationForMimeType(string pchMimeType,string pchAppKeyBuffer,uint unAppKeyBufferLen)
{
bool result = FnTable.GetDefaultApplicationForMimeType(pchMimeType,pchAppKeyBuffer,unAppKeyBufferLen);
return result;
}
public bool GetApplicationSupportedMimeTypes(string pchAppKey,string pchMimeTypesBuffer,uint unMimeTypesBuffer)
{
bool result = FnTable.GetApplicationSupportedMimeTypes(pchAppKey,pchMimeTypesBuffer,unMimeTypesBuffer);
return result;
}
public uint GetApplicationsThatSupportMimeType(string pchMimeType,string pchAppKeysThatSupportBuffer,uint unAppKeysThatSupportBuffer)
{
uint result = FnTable.GetApplicationsThatSupportMimeType(pchMimeType,pchAppKeysThatSupportBuffer,unAppKeysThatSupportBuffer);
return result;
}
public uint GetApplicationLaunchArguments(uint unHandle,string pchArgs,uint unArgs)
{
uint result = FnTable.GetApplicationLaunchArguments(unHandle,pchArgs,unArgs);
return result;
}
public EVRApplicationError GetStartingApplication(string pchAppKeyBuffer,uint unAppKeyBufferLen)
{
EVRApplicationError result = FnTable.GetStartingApplication(pchAppKeyBuffer,unAppKeyBufferLen);
@@ -2081,16 +2209,6 @@ public class CVRCompositor
{
FnTable.SuspendRendering(bSuspend);
}
public EVRCompositorError RequestScreenshot(EVRScreenshotType type,string pchDestinationFileName,string pchVRDestinationFileName)
{
EVRCompositorError result = FnTable.RequestScreenshot(type,pchDestinationFileName,pchVRDestinationFileName);
return result;
}
public EVRScreenshotType GetCurrentScreenshotType()
{
EVRScreenshotType result = FnTable.GetCurrentScreenshotType();
return result;
}
public EVRCompositorError GetMirrorTextureD3D11(EVREye eEye,IntPtr pD3D11DeviceOrResource,ref IntPtr ppD3D11ShaderResourceView)
{
EVRCompositorError result = FnTable.GetMirrorTextureD3D11(eEye,pD3D11DeviceOrResource,ref ppD3D11ShaderResourceView);
@@ -2219,6 +2337,28 @@ public class CVROverlay
EVROverlayError result = FnTable.GetOverlayAlpha(ulOverlayHandle,ref pfAlpha);
return result;
}
public EVROverlayError SetOverlayTexelAspect(ulong ulOverlayHandle,float fTexelAspect)
{
EVROverlayError result = FnTable.SetOverlayTexelAspect(ulOverlayHandle,fTexelAspect);
return result;
}
public EVROverlayError GetOverlayTexelAspect(ulong ulOverlayHandle,ref float pfTexelAspect)
{
pfTexelAspect = 0;
EVROverlayError result = FnTable.GetOverlayTexelAspect(ulOverlayHandle,ref pfTexelAspect);
return result;
}
public EVROverlayError SetOverlaySortOrder(ulong ulOverlayHandle,uint unSortOrder)
{
EVROverlayError result = FnTable.SetOverlaySortOrder(ulOverlayHandle,unSortOrder);
return result;
}
public EVROverlayError GetOverlaySortOrder(ulong ulOverlayHandle,ref uint punSortOrder)
{
punSortOrder = 0;
EVROverlayError result = FnTable.GetOverlaySortOrder(ulOverlayHandle,ref punSortOrder);
return result;
}
public EVROverlayError SetOverlayWidthInMeters(ulong ulOverlayHandle,float fWidthInMeters)
{
EVROverlayError result = FnTable.SetOverlayWidthInMeters(ulOverlayHandle,fWidthInMeters);
@@ -2621,41 +2761,41 @@ public class CVRSettings
bool result = FnTable.Sync(bForce,ref peError);
return result;
}
public bool GetBool(string pchSection,string pchSettingsKey,bool bDefaultValue,ref EVRSettingsError peError)
{
bool result = FnTable.GetBool(pchSection,pchSettingsKey,bDefaultValue,ref peError);
return result;
}
public void SetBool(string pchSection,string pchSettingsKey,bool bValue,ref EVRSettingsError peError)
{
FnTable.SetBool(pchSection,pchSettingsKey,bValue,ref peError);
}
public int GetInt32(string pchSection,string pchSettingsKey,int nDefaultValue,ref EVRSettingsError peError)
{
int result = FnTable.GetInt32(pchSection,pchSettingsKey,nDefaultValue,ref peError);
return result;
}
public void SetInt32(string pchSection,string pchSettingsKey,int nValue,ref EVRSettingsError peError)
{
FnTable.SetInt32(pchSection,pchSettingsKey,nValue,ref peError);
}
public float GetFloat(string pchSection,string pchSettingsKey,float flDefaultValue,ref EVRSettingsError peError)
{
float result = FnTable.GetFloat(pchSection,pchSettingsKey,flDefaultValue,ref peError);
return result;
}
public void SetFloat(string pchSection,string pchSettingsKey,float flValue,ref EVRSettingsError peError)
{
FnTable.SetFloat(pchSection,pchSettingsKey,flValue,ref peError);
}
public void GetString(string pchSection,string pchSettingsKey,string pchValue,uint unValueLen,string pchDefaultValue,ref EVRSettingsError peError)
{
FnTable.GetString(pchSection,pchSettingsKey,pchValue,unValueLen,pchDefaultValue,ref peError);
}
public void SetString(string pchSection,string pchSettingsKey,string pchValue,ref EVRSettingsError peError)
{
FnTable.SetString(pchSection,pchSettingsKey,pchValue,ref peError);
}
public bool GetBool(string pchSection,string pchSettingsKey,ref EVRSettingsError peError)
{
bool result = FnTable.GetBool(pchSection,pchSettingsKey,ref peError);
return result;
}
public int GetInt32(string pchSection,string pchSettingsKey,ref EVRSettingsError peError)
{
int result = FnTable.GetInt32(pchSection,pchSettingsKey,ref peError);
return result;
}
public float GetFloat(string pchSection,string pchSettingsKey,ref EVRSettingsError peError)
{
float result = FnTable.GetFloat(pchSection,pchSettingsKey,ref peError);
return result;
}
public void GetString(string pchSection,string pchSettingsKey,System.Text.StringBuilder pchValue,uint unValueLen,ref EVRSettingsError peError)
{
FnTable.GetString(pchSection,pchSettingsKey,pchValue,unValueLen,ref peError);
}
public void RemoveSection(string pchSection,ref EVRSettingsError peError)
{
FnTable.RemoveSection(pchSection,ref peError);
@@ -2714,6 +2854,26 @@ public class CVRScreenshots
}
public class CVRResources
{
IVRResources FnTable;
internal CVRResources(IntPtr pInterface)
{
FnTable = (IVRResources)Marshal.PtrToStructure(pInterface, typeof(IVRResources));
}
public uint LoadSharedResource(string pchResourceName,string pchBuffer,uint unBufferLen)
{
uint result = FnTable.LoadSharedResource(pchResourceName,pchBuffer,unBufferLen);
return result;
}
public uint GetResourceFullPath(string pchResourceName,string pchResourceTypeDirectory,string pchPathBuffer,uint unBufferLen)
{
uint result = FnTable.GetResourceFullPath(pchResourceName,pchResourceTypeDirectory,pchPathBuffer,unBufferLen);
return result;
}
}
public class OpenVRInterop
{
[DllImportAttribute("openvr_api", EntryPoint = "VR_InitInternal")]
@@ -2765,6 +2925,7 @@ public enum ETrackedDeviceClass
HMD = 1,
Controller = 2,
TrackingReference = 4,
Count = 5,
Other = 1000,
}
public enum ETrackedControllerRole
@@ -2858,6 +3019,7 @@ public enum ETrackedDeviceProperty
Prop_Axis2Type_Int32 = 3004,
Prop_Axis3Type_Int32 = 3005,
Prop_Axis4Type_Int32 = 3006,
Prop_ControllerRoleHint_Int32 = 3007,
Prop_FieldOfViewLeftDegrees_Float = 4000,
Prop_FieldOfViewRightDegrees_Float = 4001,
Prop_FieldOfViewTopDegrees_Float = 4002,
@@ -2865,6 +3027,15 @@ public enum ETrackedDeviceProperty
Prop_TrackingRangeMinimumMeters_Float = 4004,
Prop_TrackingRangeMaximumMeters_Float = 4005,
Prop_ModeLabel_String = 4006,
Prop_IconPathName_String = 5000,
Prop_NamedIconPathDeviceOff_String = 5001,
Prop_NamedIconPathDeviceSearching_String = 5002,
Prop_NamedIconPathDeviceSearchingAlert_String = 5003,
Prop_NamedIconPathDeviceReady_String = 5004,
Prop_NamedIconPathDeviceReadyAlert_String = 5005,
Prop_NamedIconPathDeviceNotReady_String = 5006,
Prop_NamedIconPathDeviceStandby_String = 5007,
Prop_NamedIconPathDeviceAlertLow_String = 5008,
Prop_VendorSpecific_Reserved_Start = 10000,
Prop_VendorSpecific_Reserved_End = 10999,
}
@@ -2886,6 +3057,7 @@ public enum EVRSubmitFlags
Submit_Default = 0,
Submit_LensDistortionAlreadyApplied = 1,
Submit_GlRenderBuffer = 2,
Submit_VulkanTexture = 4,
}
public enum EVRState
{
@@ -2897,6 +3069,7 @@ public enum EVRState
Ready_Alert = 4,
NotReady = 5,
Standby = 6,
Ready_Alert_Low = 7,
}
public enum EVREventType
{
@@ -2910,6 +3083,8 @@ public enum EVREventType
VREvent_EnterStandbyMode = 106,
VREvent_LeaveStandbyMode = 107,
VREvent_TrackedDeviceRoleChanged = 108,
VREvent_WatchdogWakeUpRequested = 109,
VREvent_LensDistortionChanged = 110,
VREvent_ButtonPress = 200,
VREvent_ButtonUnpress = 201,
VREvent_ButtonTouch = 202,
@@ -2921,6 +3096,7 @@ public enum EVREventType
VREvent_FocusLeave = 304,
VREvent_Scroll = 305,
VREvent_TouchPadMove = 306,
VREvent_OverlayFocusChanged = 307,
VREvent_InputFocusCaptured = 400,
VREvent_InputFocusReleased = 401,
VREvent_SceneFocusLost = 402,
@@ -2949,10 +3125,12 @@ public enum EVREventType
VREvent_DashboardGuideButtonUp = 515,
VREvent_ScreenshotTriggered = 516,
VREvent_ImageFailed = 517,
VREvent_DashboardOverlayCreated = 518,
VREvent_RequestScreenshot = 520,
VREvent_ScreenshotTaken = 521,
VREvent_ScreenshotFailed = 522,
VREvent_SubmitScreenshotToDashboard = 523,
VREvent_ScreenshotProgressToDashboard = 524,
VREvent_Notification_Shown = 600,
VREvent_Notification_Hidden = 601,
VREvent_Notification_BeginInteraction = 602,
@@ -2973,6 +3151,7 @@ public enum EVREventType
VREvent_ReprojectionSettingHasChanged = 852,
VREvent_ModelSkinSettingsHaveChanged = 853,
VREvent_EnvironmentSettingsHaveChanged = 854,
VREvent_PowerSettingsHaveChanged = 855,
VREvent_StatusUpdate = 900,
VREvent_MCImageUpdated = 1000,
VREvent_FirmwareUpdateStarted = 1100,
@@ -2984,6 +3163,7 @@ public enum EVREventType
VREvent_ApplicationTransitionAborted = 1301,
VREvent_ApplicationTransitionNewAppStarted = 1302,
VREvent_ApplicationListUpdated = 1303,
VREvent_ApplicationMimeTypeLoad = 1304,
VREvent_Compositor_MirrorWindowShown = 1400,
VREvent_Compositor_MirrorWindowHidden = 1401,
VREvent_Compositor_ChaperoneBoundsShown = 1410,
@@ -2992,6 +3172,7 @@ public enum EVREventType
VREvent_TrackedCamera_StopVideoStream = 1501,
VREvent_TrackedCamera_PauseVideoStream = 1502,
VREvent_TrackedCamera_ResumeVideoStream = 1503,
VREvent_TrackedCamera_EditingSurface = 1550,
VREvent_PerformanceTest_EnableCapture = 1600,
VREvent_PerformanceTest_DisableCapture = 1601,
VREvent_PerformanceTest_FidelityLevel = 1602,
@@ -3016,6 +3197,7 @@ public enum EVRButtonId
k_EButton_DPad_Right = 5,
k_EButton_DPad_Down = 6,
k_EButton_A = 7,
k_EButton_ProximitySensor = 31,
k_EButton_Axis0 = 32,
k_EButton_Axis1 = 33,
k_EButton_Axis2 = 34,
@@ -3072,7 +3254,7 @@ public enum EVROverlayError
RequestFailed = 23,
InvalidTexture = 24,
UnableToLoadFile = 25,
VROVerlayError_KeyboardAlreadyInUse = 26,
KeyboardAlreadyInUse = 26,
NoNeighbor = 27,
}
public enum EVRApplicationType
@@ -3083,6 +3265,8 @@ public enum EVRApplicationType
VRApplication_Background = 3,
VRApplication_Utility = 4,
VRApplication_VRMonitor = 5,
VRApplication_SteamWatchdog = 6,
VRApplication_Max = 7,
}
public enum EVRFirmwareError
{
@@ -3127,6 +3311,14 @@ public enum EVRInitError
Init_NotSupportedWithCompositor = 122,
Init_NotAvailableToUtilityApps = 123,
Init_Internal = 124,
Init_HmdDriverIdIsNone = 125,
Init_HmdNotFoundPresenceFailed = 126,
Init_VRMonitorNotFound = 127,
Init_VRMonitorStartupFailed = 128,
Init_LowPowerWatchdogNotSupported = 129,
Init_InvalidApplicationType = 130,
Init_NotAvailableToWatchdogApps = 131,
Init_WatchdogDisabledInSettings = 132,
Driver_Failed = 200,
Driver_Unknown = 201,
Driver_HmdUnknown = 202,
@@ -3136,12 +3328,18 @@ public enum EVRInitError
Driver_NotCalibrated = 206,
Driver_CalibrationInvalid = 207,
Driver_HmdDisplayNotFound = 208,
Driver_TrackedDeviceInterfaceUnknown = 209,
Driver_HmdDriverIdOutOfBounds = 211,
Driver_HmdDisplayMirrored = 212,
IPC_ServerInitFailed = 300,
IPC_ConnectFailed = 301,
IPC_SharedStateInitFailed = 302,
IPC_CompositorInitFailed = 303,
IPC_MutexInitFailed = 304,
IPC_Failed = 305,
IPC_CompositorConnectFailed = 306,
IPC_CompositorInvalidConnectResponse = 307,
IPC_ConnectFailedAfterMultipleAttempts = 308,
Compositor_Failed = 400,
Compositor_D3D11HardwareRequired = 401,
Compositor_FirmwareRequiresUpdate = 402,
@@ -3314,6 +3512,7 @@ public enum VROverlayFlags
SideBySide_Crossed = 11,
Panorama = 12,
StereoPanorama = 13,
SortWithNonSceneOverlays = 14,
}
public enum EGamepadTextInputMode
{
@@ -3378,6 +3577,8 @@ public enum EVRSettingsError
IPCFailed = 1,
WriteFailed = 2,
ReadFailed = 3,
JsonParseFailed = 4,
UnsetSettingHasNoDefault = 5,
}
public enum EVRScreenshotError
{
@@ -3525,6 +3726,19 @@ public enum EVRScreenshotError
public float uMax;
public float vMax;
}
[StructLayout(LayoutKind.Sequential)] public struct VulkanData_t
{
public ulong m_nImage;
public IntPtr m_pDevice; // struct VkDevice_T *
public IntPtr m_pPhysicalDevice; // struct VkPhysicalDevice_T *
public IntPtr m_pInstance; // struct VkInstance_T *
public IntPtr m_pQueue; // struct VkQueue_T *
public uint m_nQueueFamilyIndex;
public uint m_nWidth;
public uint m_nHeight;
public uint m_nFormat;
public uint m_nSampleCount;
}
[StructLayout(LayoutKind.Sequential)] public struct VREvent_Controller_t
{
public uint button;
@@ -3604,6 +3818,20 @@ public enum EVRScreenshotError
public uint handle;
public uint type;
}
[StructLayout(LayoutKind.Sequential)] public struct VREvent_ScreenshotProgress_t
{
public float progress;
}
[StructLayout(LayoutKind.Sequential)] public struct VREvent_ApplicationLaunch_t
{
public uint pid;
public uint unArgsHandle;
}
[StructLayout(LayoutKind.Sequential)] public struct VREvent_EditingCameraSurface_t
{
public ulong overlayHandle;
public uint nVisualMode;
}
[StructLayout(LayoutKind.Sequential)] public struct VREvent_t
{
public uint eventType;
@@ -3671,8 +3899,10 @@ public enum EVRScreenshotError
public uint m_nFrameIndex;
public uint m_nNumFramePresents;
public uint m_nNumDroppedFrames;
public uint m_nReprojectionFlags;
public double m_flSystemTimeInSeconds;
public float m_flSceneRenderGpuMs;
public float m_flPreSubmitGpuMs;
public float m_flPostSubmitGpuMs;
public float m_flTotalRenderGpuMs;
public float m_flCompositorRenderGpuMs;
public float m_flCompositorRenderCpuMs;
@@ -3688,8 +3918,6 @@ public enum EVRScreenshotError
public float m_flCompositorUpdateEndMs;
public float m_flCompositorRenderStartMs;
public TrackedDevicePose_t m_HmdPose;
public int m_nFidelityLevel;
public uint m_nReprojectionFlags;
}
[StructLayout(LayoutKind.Sequential)] public struct Compositor_CumulativeStats
{
@@ -3768,6 +3996,7 @@ public enum EVRScreenshotError
public IntPtr m_pVRChaperoneSetup; // class vr::IVRChaperoneSetup *
public IntPtr m_pVRCompositor; // class vr::IVRCompositor *
public IntPtr m_pVROverlay; // class vr::IVROverlay *
public IntPtr m_pVRResources; // class vr::IVRResources *
public IntPtr m_pVRRenderModels; // class vr::IVRRenderModels *
public IntPtr m_pVRExtendedDisplay; // class vr::IVRExtendedDisplay *
public IntPtr m_pVRSettings; // class vr::IVRSettings *
@@ -3833,14 +4062,16 @@ public class OpenVR
public const string IVRExtendedDisplay_Version = "IVRExtendedDisplay_001";
public const string IVRTrackedCamera_Version = "IVRTrackedCamera_003";
public const uint k_unMaxApplicationKeyLength = 128;
public const string IVRApplications_Version = "IVRApplications_005";
public const string k_pch_MimeType_HomeApp = "vr/home";
public const string k_pch_MimeType_GameTheater = "vr/game_theater";
public const string IVRApplications_Version = "IVRApplications_006";
public const string IVRChaperone_Version = "IVRChaperone_003";
public const string IVRChaperoneSetup_Version = "IVRChaperoneSetup_005";
public const string IVRCompositor_Version = "IVRCompositor_015";
public const string IVRCompositor_Version = "IVRCompositor_016";
public const uint k_unVROverlayMaxKeyLength = 128;
public const uint k_unVROverlayMaxNameLength = 128;
public const uint k_unMaxOverlayCount = 32;
public const string IVROverlay_Version = "IVROverlay_012";
public const uint k_unMaxOverlayCount = 64;
public const string IVROverlay_Version = "IVROverlay_013";
public const string k_pch_Controller_Component_GDC2015 = "gdc2015";
public const string k_pch_Controller_Component_Base = "base";
public const string k_pch_Controller_Component_Tip = "tip";
@@ -3850,7 +4081,7 @@ public class OpenVR
public const uint k_unNotificationTextMaxSize = 256;
public const string IVRNotifications_Version = "IVRNotifications_002";
public const uint k_unMaxSettingsKeyLength = 128;
public const string IVRSettings_Version = "IVRSettings_001";
public const string IVRSettings_Version = "IVRSettings_002";
public const string k_pch_SteamVR_Section = "steamvr";
public const string k_pch_SteamVR_RequireHmd_String = "requireHmd";
public const string k_pch_SteamVR_ForcedDriverKey_String = "forcedDriver";
@@ -3871,9 +4102,6 @@ public class OpenVR
public const string k_pch_SteamVR_PlayAreaColor_String = "playAreaColor";
public const string k_pch_SteamVR_ShowStage_Bool = "showStage";
public const string k_pch_SteamVR_ActivateMultipleDrivers_Bool = "activateMultipleDrivers";
public const string k_pch_SteamVR_PowerOffOnExit_Bool = "powerOffOnExit";
public const string k_pch_SteamVR_StandbyAppRunningTimeout_Float = "standbyAppRunningTimeout";
public const string k_pch_SteamVR_StandbyNoAppTimeout_Float = "standbyNoAppTimeout";
public const string k_pch_SteamVR_DirectMode_Bool = "directMode";
public const string k_pch_SteamVR_DirectModeEdidVid_Int32 = "directModeEdidVid";
public const string k_pch_SteamVR_DirectModeEdidPid_Int32 = "directModeEdidPid";
@@ -3887,14 +4115,17 @@ public class OpenVR
public const string k_pch_SteamVR_ForceFadeOnBadTracking_Bool = "forceFadeOnBadTracking";
public const string k_pch_SteamVR_DefaultMirrorView_Int32 = "defaultMirrorView";
public const string k_pch_SteamVR_ShowMirrorView_Bool = "showMirrorView";
public const string k_pch_SteamVR_MirrorViewGeometry_String = "mirrorViewGeometry";
public const string k_pch_SteamVR_StartMonitorFromAppLaunch = "startMonitorFromAppLaunch";
public const string k_pch_SteamVR_EnableHomeApp = "enableHomeApp";
public const string k_pch_SteamVR_SetInitialDefaultHomeApp = "setInitialDefaultHomeApp";
public const string k_pch_SteamVR_CycleBackgroundImageTimeSec_Int32 = "CycleBackgroundImageTimeSec";
public const string k_pch_SteamVR_RetailDemo_Bool = "retailDemo";
public const string k_pch_Lighthouse_Section = "driver_lighthouse";
public const string k_pch_Lighthouse_DisableIMU_Bool = "disableimu";
public const string k_pch_Lighthouse_UseDisambiguation_String = "usedisambiguation";
public const string k_pch_Lighthouse_DisambiguationDebug_Int32 = "disambiguationdebug";
public const string k_pch_Lighthouse_PrimaryBasestation_Int32 = "primarybasestation";
public const string k_pch_Lighthouse_LighthouseName_String = "lighthousename";
public const string k_pch_Lighthouse_MaxIncidenceAngleDegrees_Float = "maxincidenceangledegrees";
public const string k_pch_Lighthouse_UseLighthouseDirect_Bool = "uselighthousedirect";
public const string k_pch_Lighthouse_DBHistory_Bool = "dbhistory";
public const string k_pch_Null_Section = "driver_null";
public const string k_pch_Null_EnableNullDriver_Bool = "enable";
@@ -3910,7 +4141,8 @@ public class OpenVR
public const string k_pch_Null_DisplayFrequency_Float = "displayFrequency";
public const string k_pch_UserInterface_Section = "userinterface";
public const string k_pch_UserInterface_StatusAlwaysOnTop_Bool = "StatusAlwaysOnTop";
public const string k_pch_UserInterface_EnableScreenshots_Bool = "EnableScreenshots";
public const string k_pch_UserInterface_Screenshots_Bool = "screenshots";
public const string k_pch_UserInterface_ScreenshotType_Int = "screenshotType";
public const string k_pch_Notifications_Section = "notifications";
public const string k_pch_Notifications_DoNotDisturb_Bool = "DoNotDisturb";
public const string k_pch_Keyboard_Section = "keyboard";
@@ -3947,6 +4179,7 @@ public class OpenVR
public const string k_pch_Camera_BoundsColorGammaG_Int32 = "cameraBoundsColorGammaG";
public const string k_pch_Camera_BoundsColorGammaB_Int32 = "cameraBoundsColorGammaB";
public const string k_pch_Camera_BoundsColorGammaA_Int32 = "cameraBoundsColorGammaA";
public const string k_pch_Camera_BoundsStrength_Int32 = "cameraBoundsStrength";
public const string k_pch_audio_Section = "audio";
public const string k_pch_audio_OnPlaybackDevice_String = "onPlaybackDevice";
public const string k_pch_audio_OnRecordDevice_String = "onRecordDevice";
@@ -3954,8 +4187,18 @@ public class OpenVR
public const string k_pch_audio_OffPlaybackDevice_String = "offPlaybackDevice";
public const string k_pch_audio_OffRecordDevice_String = "offRecordDevice";
public const string k_pch_audio_VIVEHDMIGain = "viveHDMIGain";
public const string k_pch_Power_Section = "power";
public const string k_pch_Power_PowerOffOnExit_Bool = "powerOffOnExit";
public const string k_pch_Power_TurnOffScreensTimeout_Float = "turnOffScreensTimeout";
public const string k_pch_Power_TurnOffControllersTimeout_Float = "turnOffControllersTimeout";
public const string k_pch_Power_ReturnToWatchdogTimeout_Float = "returnToWatchdogTimeout";
public const string k_pch_Power_AutoLaunchSteamVROnButtonPress = "autoLaunchSteamVROnButtonPress";
public const string k_pch_Dashboard_Section = "dashboard";
public const string k_pch_Dashboard_EnableDashboard_Bool = "enableDashboard";
public const string k_pch_Dashboard_ArcadeMode_Bool = "arcadeMode";
public const string k_pch_modelskin_Section = "modelskins";
public const string IVRScreenshots_Version = "IVRScreenshots_001";
public const string IVRResources_Version = "IVRResources_001";
static uint VRToken { get; set; }
@@ -3977,6 +4220,7 @@ public class OpenVR
m_pVRSettings = null;
m_pVRApplications = null;
m_pVRScreenshots = null;
m_pVRTrackedCamera = null;
}
void CheckClear()
@@ -4118,6 +4362,19 @@ public class OpenVR
return m_pVRScreenshots;
}
public CVRTrackedCamera VRTrackedCamera()
{
CheckClear();
if (m_pVRTrackedCamera == null)
{
var eError = EVRInitError.None;
var pInterface = OpenVRInterop.GetGenericInterface(FnTable_Prefix+IVRTrackedCamera_Version, ref eError);
if (pInterface != IntPtr.Zero && eError == EVRInitError.None)
m_pVRTrackedCamera = new CVRTrackedCamera(pInterface);
}
return m_pVRTrackedCamera;
}
private CVRSystem m_pVRSystem;
private CVRChaperone m_pVRChaperone;
private CVRChaperoneSetup m_pVRChaperoneSetup;
@@ -4128,6 +4385,7 @@ public class OpenVR
private CVRSettings m_pVRSettings;
private CVRApplications m_pVRApplications;
private CVRScreenshots m_pVRScreenshots;
private CVRTrackedCamera m_pVRTrackedCamera;
};
private static COpenVRContext _OpenVRInternal_ModuleContext = null;
@@ -4147,10 +4405,11 @@ public class OpenVR
public static CVRCompositor Compositor { get { return OpenVRInternal_ModuleContext.VRCompositor(); } }
public static CVROverlay Overlay { get { return OpenVRInternal_ModuleContext.VROverlay(); } }
public static CVRRenderModels RenderModels { get { return OpenVRInternal_ModuleContext.VRRenderModels(); } }
public static CVRApplications Applications { get { return OpenVRInternal_ModuleContext.VRApplications(); } }
public static CVRSettings Settings { get { return OpenVRInternal_ModuleContext.VRSettings(); } }
public static CVRExtendedDisplay ExtendedDisplay { get { return OpenVRInternal_ModuleContext.VRExtendedDisplay(); } }
public static CVRSettings Settings { get { return OpenVRInternal_ModuleContext.VRSettings(); } }
public static CVRApplications Applications { get { return OpenVRInternal_ModuleContext.VRApplications(); } }
public static CVRScreenshots Screenshots { get { return OpenVRInternal_ModuleContext.VRScreenshots(); } }
public static CVRTrackedCamera TrackedCamera { get { return OpenVRInternal_ModuleContext.VRTrackedCamera(); } }
/** Finds the active installation of vrclient.dll and initializes it */
public static CVRSystem Init(ref EVRInitError peError, EVRApplicationType eApplicationType = EVRApplicationType.VRApplication_Scene)

View File

@@ -1,6 +1,7 @@
{"typedefs":[{"typedef": "vr::glSharedTextureHandle_t","type": "void *"}
,{"typedef": "vr::glInt_t","type": "int32_t"}
,{"typedef": "vr::glUInt_t","type": "uint32_t"}
,{"typedef": "vr::SharedTextureHandle_t","type": "uint64_t"}
,{"typedef": "vr::TrackedDeviceIndex_t","type": "uint32_t"}
,{"typedef": "vr::VREvent_Data_t","type": "union VREvent_Data_t"}
,{"typedef": "vr::VRControllerState_t","type": "struct vr::VRControllerState001_t"}
@@ -53,6 +54,7 @@
,{"name": "TrackedDeviceClass_HMD","value": "1"}
,{"name": "TrackedDeviceClass_Controller","value": "2"}
,{"name": "TrackedDeviceClass_TrackingReference","value": "4"}
,{"name": "TrackedDeviceClass_Count","value": "5"}
,{"name": "TrackedDeviceClass_Other","value": "1000"}
]}
, {"enumname": "vr::ETrackedControllerRole","values": [
@@ -143,6 +145,7 @@
,{"name": "Prop_Axis2Type_Int32","value": "3004"}
,{"name": "Prop_Axis3Type_Int32","value": "3005"}
,{"name": "Prop_Axis4Type_Int32","value": "3006"}
,{"name": "Prop_ControllerRoleHint_Int32","value": "3007"}
,{"name": "Prop_FieldOfViewLeftDegrees_Float","value": "4000"}
,{"name": "Prop_FieldOfViewRightDegrees_Float","value": "4001"}
,{"name": "Prop_FieldOfViewTopDegrees_Float","value": "4002"}
@@ -150,6 +153,15 @@
,{"name": "Prop_TrackingRangeMinimumMeters_Float","value": "4004"}
,{"name": "Prop_TrackingRangeMaximumMeters_Float","value": "4005"}
,{"name": "Prop_ModeLabel_String","value": "4006"}
,{"name": "Prop_IconPathName_String","value": "5000"}
,{"name": "Prop_NamedIconPathDeviceOff_String","value": "5001"}
,{"name": "Prop_NamedIconPathDeviceSearching_String","value": "5002"}
,{"name": "Prop_NamedIconPathDeviceSearchingAlert_String","value": "5003"}
,{"name": "Prop_NamedIconPathDeviceReady_String","value": "5004"}
,{"name": "Prop_NamedIconPathDeviceReadyAlert_String","value": "5005"}
,{"name": "Prop_NamedIconPathDeviceNotReady_String","value": "5006"}
,{"name": "Prop_NamedIconPathDeviceStandby_String","value": "5007"}
,{"name": "Prop_NamedIconPathDeviceAlertLow_String","value": "5008"}
,{"name": "Prop_VendorSpecific_Reserved_Start","value": "10000"}
,{"name": "Prop_VendorSpecific_Reserved_End","value": "10999"}
]}
@@ -169,6 +181,7 @@
{"name": "Submit_Default","value": "0"}
,{"name": "Submit_LensDistortionAlreadyApplied","value": "1"}
,{"name": "Submit_GlRenderBuffer","value": "2"}
,{"name": "Submit_VulkanTexture","value": "4"}
]}
, {"enumname": "vr::EVRState","values": [
{"name": "VRState_Undefined","value": "-1"}
@@ -179,6 +192,7 @@
,{"name": "VRState_Ready_Alert","value": "4"}
,{"name": "VRState_NotReady","value": "5"}
,{"name": "VRState_Standby","value": "6"}
,{"name": "VRState_Ready_Alert_Low","value": "7"}
]}
, {"enumname": "vr::EVREventType","values": [
{"name": "VREvent_None","value": "0"}
@@ -191,6 +205,8 @@
,{"name": "VREvent_EnterStandbyMode","value": "106"}
,{"name": "VREvent_LeaveStandbyMode","value": "107"}
,{"name": "VREvent_TrackedDeviceRoleChanged","value": "108"}
,{"name": "VREvent_WatchdogWakeUpRequested","value": "109"}
,{"name": "VREvent_LensDistortionChanged","value": "110"}
,{"name": "VREvent_ButtonPress","value": "200"}
,{"name": "VREvent_ButtonUnpress","value": "201"}
,{"name": "VREvent_ButtonTouch","value": "202"}
@@ -202,6 +218,7 @@
,{"name": "VREvent_FocusLeave","value": "304"}
,{"name": "VREvent_Scroll","value": "305"}
,{"name": "VREvent_TouchPadMove","value": "306"}
,{"name": "VREvent_OverlayFocusChanged","value": "307"}
,{"name": "VREvent_InputFocusCaptured","value": "400"}
,{"name": "VREvent_InputFocusReleased","value": "401"}
,{"name": "VREvent_SceneFocusLost","value": "402"}
@@ -230,10 +247,12 @@
,{"name": "VREvent_DashboardGuideButtonUp","value": "515"}
,{"name": "VREvent_ScreenshotTriggered","value": "516"}
,{"name": "VREvent_ImageFailed","value": "517"}
,{"name": "VREvent_DashboardOverlayCreated","value": "518"}
,{"name": "VREvent_RequestScreenshot","value": "520"}
,{"name": "VREvent_ScreenshotTaken","value": "521"}
,{"name": "VREvent_ScreenshotFailed","value": "522"}
,{"name": "VREvent_SubmitScreenshotToDashboard","value": "523"}
,{"name": "VREvent_ScreenshotProgressToDashboard","value": "524"}
,{"name": "VREvent_Notification_Shown","value": "600"}
,{"name": "VREvent_Notification_Hidden","value": "601"}
,{"name": "VREvent_Notification_BeginInteraction","value": "602"}
@@ -254,6 +273,7 @@
,{"name": "VREvent_ReprojectionSettingHasChanged","value": "852"}
,{"name": "VREvent_ModelSkinSettingsHaveChanged","value": "853"}
,{"name": "VREvent_EnvironmentSettingsHaveChanged","value": "854"}
,{"name": "VREvent_PowerSettingsHaveChanged","value": "855"}
,{"name": "VREvent_StatusUpdate","value": "900"}
,{"name": "VREvent_MCImageUpdated","value": "1000"}
,{"name": "VREvent_FirmwareUpdateStarted","value": "1100"}
@@ -265,6 +285,7 @@
,{"name": "VREvent_ApplicationTransitionAborted","value": "1301"}
,{"name": "VREvent_ApplicationTransitionNewAppStarted","value": "1302"}
,{"name": "VREvent_ApplicationListUpdated","value": "1303"}
,{"name": "VREvent_ApplicationMimeTypeLoad","value": "1304"}
,{"name": "VREvent_Compositor_MirrorWindowShown","value": "1400"}
,{"name": "VREvent_Compositor_MirrorWindowHidden","value": "1401"}
,{"name": "VREvent_Compositor_ChaperoneBoundsShown","value": "1410"}
@@ -273,6 +294,7 @@
,{"name": "VREvent_TrackedCamera_StopVideoStream","value": "1501"}
,{"name": "VREvent_TrackedCamera_PauseVideoStream","value": "1502"}
,{"name": "VREvent_TrackedCamera_ResumeVideoStream","value": "1503"}
,{"name": "VREvent_TrackedCamera_EditingSurface","value": "1550"}
,{"name": "VREvent_PerformanceTest_EnableCapture","value": "1600"}
,{"name": "VREvent_PerformanceTest_DisableCapture","value": "1601"}
,{"name": "VREvent_PerformanceTest_FidelityLevel","value": "1602"}
@@ -295,6 +317,7 @@
,{"name": "k_EButton_DPad_Right","value": "5"}
,{"name": "k_EButton_DPad_Down","value": "6"}
,{"name": "k_EButton_A","value": "7"}
,{"name": "k_EButton_ProximitySensor","value": "31"}
,{"name": "k_EButton_Axis0","value": "32"}
,{"name": "k_EButton_Axis1","value": "33"}
,{"name": "k_EButton_Axis2","value": "34"}
@@ -346,7 +369,7 @@
,{"name": "VROverlayError_RequestFailed","value": "23"}
,{"name": "VROverlayError_InvalidTexture","value": "24"}
,{"name": "VROverlayError_UnableToLoadFile","value": "25"}
,{"name": "VROVerlayError_KeyboardAlreadyInUse","value": "26"}
,{"name": "VROverlayError_KeyboardAlreadyInUse","value": "26"}
,{"name": "VROverlayError_NoNeighbor","value": "27"}
]}
, {"enumname": "vr::EVRApplicationType","values": [
@@ -356,6 +379,8 @@
,{"name": "VRApplication_Background","value": "3"}
,{"name": "VRApplication_Utility","value": "4"}
,{"name": "VRApplication_VRMonitor","value": "5"}
,{"name": "VRApplication_SteamWatchdog","value": "6"}
,{"name": "VRApplication_Max","value": "7"}
]}
, {"enumname": "vr::EVRFirmwareError","values": [
{"name": "VRFirmwareError_None","value": "0"}
@@ -397,6 +422,14 @@
,{"name": "VRInitError_Init_NotSupportedWithCompositor","value": "122"}
,{"name": "VRInitError_Init_NotAvailableToUtilityApps","value": "123"}
,{"name": "VRInitError_Init_Internal","value": "124"}
,{"name": "VRInitError_Init_HmdDriverIdIsNone","value": "125"}
,{"name": "VRInitError_Init_HmdNotFoundPresenceFailed","value": "126"}
,{"name": "VRInitError_Init_VRMonitorNotFound","value": "127"}
,{"name": "VRInitError_Init_VRMonitorStartupFailed","value": "128"}
,{"name": "VRInitError_Init_LowPowerWatchdogNotSupported","value": "129"}
,{"name": "VRInitError_Init_InvalidApplicationType","value": "130"}
,{"name": "VRInitError_Init_NotAvailableToWatchdogApps","value": "131"}
,{"name": "VRInitError_Init_WatchdogDisabledInSettings","value": "132"}
,{"name": "VRInitError_Driver_Failed","value": "200"}
,{"name": "VRInitError_Driver_Unknown","value": "201"}
,{"name": "VRInitError_Driver_HmdUnknown","value": "202"}
@@ -406,12 +439,18 @@
,{"name": "VRInitError_Driver_NotCalibrated","value": "206"}
,{"name": "VRInitError_Driver_CalibrationInvalid","value": "207"}
,{"name": "VRInitError_Driver_HmdDisplayNotFound","value": "208"}
,{"name": "VRInitError_Driver_TrackedDeviceInterfaceUnknown","value": "209"}
,{"name": "VRInitError_Driver_HmdDriverIdOutOfBounds","value": "211"}
,{"name": "VRInitError_Driver_HmdDisplayMirrored","value": "212"}
,{"name": "VRInitError_IPC_ServerInitFailed","value": "300"}
,{"name": "VRInitError_IPC_ConnectFailed","value": "301"}
,{"name": "VRInitError_IPC_SharedStateInitFailed","value": "302"}
,{"name": "VRInitError_IPC_CompositorInitFailed","value": "303"}
,{"name": "VRInitError_IPC_MutexInitFailed","value": "304"}
,{"name": "VRInitError_IPC_Failed","value": "305"}
,{"name": "VRInitError_IPC_CompositorConnectFailed","value": "306"}
,{"name": "VRInitError_IPC_CompositorInvalidConnectResponse","value": "307"}
,{"name": "VRInitError_IPC_ConnectFailedAfterMultipleAttempts","value": "308"}
,{"name": "VRInitError_Compositor_Failed","value": "400"}
,{"name": "VRInitError_Compositor_D3D11HardwareRequired","value": "401"}
,{"name": "VRInitError_Compositor_FirmwareRequiresUpdate","value": "402"}
@@ -570,6 +609,7 @@
,{"name": "VROverlayFlags_SideBySide_Crossed","value": "11"}
,{"name": "VROverlayFlags_Panorama","value": "12"}
,{"name": "VROverlayFlags_StereoPanorama","value": "13"}
,{"name": "VROverlayFlags_SortWithNonSceneOverlays","value": "14"}
]}
, {"enumname": "vr::EGamepadTextInputMode","values": [
{"name": "k_EGamepadTextInputModeNormal","value": "0"}
@@ -626,6 +666,8 @@
,{"name": "VRSettingsError_IPCFailed","value": "1"}
,{"name": "VRSettingsError_WriteFailed","value": "2"}
,{"name": "VRSettingsError_ReadFailed","value": "3"}
,{"name": "VRSettingsError_JsonParseFailed","value": "4"}
,{"name": "VRSettingsError_UnsetSettingHasNoDefault","value": "5"}
]}
, {"enumname": "vr::EVRScreenshotError","values": [
{"name": "VRScreenshotError_None","value": "0"}
@@ -665,21 +707,25 @@
,{
"constname": "k_unMaxApplicationKeyLength","consttype": "const uint32_t", "constval": "128"}
,{
"constname": "IVRApplications_Version","consttype": "const char *const", "constval": "IVRApplications_005"}
"constname": "k_pch_MimeType_HomeApp","consttype": "const char *const", "constval": "vr/home"}
,{
"constname": "k_pch_MimeType_GameTheater","consttype": "const char *const", "constval": "vr/game_theater"}
,{
"constname": "IVRApplications_Version","consttype": "const char *const", "constval": "IVRApplications_006"}
,{
"constname": "IVRChaperone_Version","consttype": "const char *const", "constval": "IVRChaperone_003"}
,{
"constname": "IVRChaperoneSetup_Version","consttype": "const char *const", "constval": "IVRChaperoneSetup_005"}
,{
"constname": "IVRCompositor_Version","consttype": "const char *const", "constval": "IVRCompositor_015"}
"constname": "IVRCompositor_Version","consttype": "const char *const", "constval": "IVRCompositor_016"}
,{
"constname": "k_unVROverlayMaxKeyLength","consttype": "const uint32_t", "constval": "128"}
,{
"constname": "k_unVROverlayMaxNameLength","consttype": "const uint32_t", "constval": "128"}
,{
"constname": "k_unMaxOverlayCount","consttype": "const uint32_t", "constval": "32"}
"constname": "k_unMaxOverlayCount","consttype": "const uint32_t", "constval": "64"}
,{
"constname": "IVROverlay_Version","consttype": "const char *const", "constval": "IVROverlay_012"}
"constname": "IVROverlay_Version","consttype": "const char *const", "constval": "IVROverlay_013"}
,{
"constname": "k_pch_Controller_Component_GDC2015","consttype": "const char *const", "constval": "gdc2015"}
,{
@@ -699,7 +745,7 @@
,{
"constname": "k_unMaxSettingsKeyLength","consttype": "const uint32_t", "constval": "128"}
,{
"constname": "IVRSettings_Version","consttype": "const char *const", "constval": "IVRSettings_001"}
"constname": "IVRSettings_Version","consttype": "const char *const", "constval": "IVRSettings_002"}
,{
"constname": "k_pch_SteamVR_Section","consttype": "const char *const", "constval": "steamvr"}
,{
@@ -740,12 +786,6 @@
"constname": "k_pch_SteamVR_ShowStage_Bool","consttype": "const char *const", "constval": "showStage"}
,{
"constname": "k_pch_SteamVR_ActivateMultipleDrivers_Bool","consttype": "const char *const", "constval": "activateMultipleDrivers"}
,{
"constname": "k_pch_SteamVR_PowerOffOnExit_Bool","consttype": "const char *const", "constval": "powerOffOnExit"}
,{
"constname": "k_pch_SteamVR_StandbyAppRunningTimeout_Float","consttype": "const char *const", "constval": "standbyAppRunningTimeout"}
,{
"constname": "k_pch_SteamVR_StandbyNoAppTimeout_Float","consttype": "const char *const", "constval": "standbyNoAppTimeout"}
,{
"constname": "k_pch_SteamVR_DirectMode_Bool","consttype": "const char *const", "constval": "directMode"}
,{
@@ -772,6 +812,18 @@
"constname": "k_pch_SteamVR_DefaultMirrorView_Int32","consttype": "const char *const", "constval": "defaultMirrorView"}
,{
"constname": "k_pch_SteamVR_ShowMirrorView_Bool","consttype": "const char *const", "constval": "showMirrorView"}
,{
"constname": "k_pch_SteamVR_MirrorViewGeometry_String","consttype": "const char *const", "constval": "mirrorViewGeometry"}
,{
"constname": "k_pch_SteamVR_StartMonitorFromAppLaunch","consttype": "const char *const", "constval": "startMonitorFromAppLaunch"}
,{
"constname": "k_pch_SteamVR_EnableHomeApp","consttype": "const char *const", "constval": "enableHomeApp"}
,{
"constname": "k_pch_SteamVR_SetInitialDefaultHomeApp","consttype": "const char *const", "constval": "setInitialDefaultHomeApp"}
,{
"constname": "k_pch_SteamVR_CycleBackgroundImageTimeSec_Int32","consttype": "const char *const", "constval": "CycleBackgroundImageTimeSec"}
,{
"constname": "k_pch_SteamVR_RetailDemo_Bool","consttype": "const char *const", "constval": "retailDemo"}
,{
"constname": "k_pch_Lighthouse_Section","consttype": "const char *const", "constval": "driver_lighthouse"}
,{
@@ -782,12 +834,6 @@
"constname": "k_pch_Lighthouse_DisambiguationDebug_Int32","consttype": "const char *const", "constval": "disambiguationdebug"}
,{
"constname": "k_pch_Lighthouse_PrimaryBasestation_Int32","consttype": "const char *const", "constval": "primarybasestation"}
,{
"constname": "k_pch_Lighthouse_LighthouseName_String","consttype": "const char *const", "constval": "lighthousename"}
,{
"constname": "k_pch_Lighthouse_MaxIncidenceAngleDegrees_Float","consttype": "const char *const", "constval": "maxincidenceangledegrees"}
,{
"constname": "k_pch_Lighthouse_UseLighthouseDirect_Bool","consttype": "const char *const", "constval": "uselighthousedirect"}
,{
"constname": "k_pch_Lighthouse_DBHistory_Bool","consttype": "const char *const", "constval": "dbhistory"}
,{
@@ -819,7 +865,9 @@
,{
"constname": "k_pch_UserInterface_StatusAlwaysOnTop_Bool","consttype": "const char *const", "constval": "StatusAlwaysOnTop"}
,{
"constname": "k_pch_UserInterface_EnableScreenshots_Bool","consttype": "const char *const", "constval": "EnableScreenshots"}
"constname": "k_pch_UserInterface_Screenshots_Bool","consttype": "const char *const", "constval": "screenshots"}
,{
"constname": "k_pch_UserInterface_ScreenshotType_Int","consttype": "const char *const", "constval": "screenshotType"}
,{
"constname": "k_pch_Notifications_Section","consttype": "const char *const", "constval": "notifications"}
,{
@@ -892,6 +940,8 @@
"constname": "k_pch_Camera_BoundsColorGammaB_Int32","consttype": "const char *const", "constval": "cameraBoundsColorGammaB"}
,{
"constname": "k_pch_Camera_BoundsColorGammaA_Int32","consttype": "const char *const", "constval": "cameraBoundsColorGammaA"}
,{
"constname": "k_pch_Camera_BoundsStrength_Int32","consttype": "const char *const", "constval": "cameraBoundsStrength"}
,{
"constname": "k_pch_audio_Section","consttype": "const char *const", "constval": "audio"}
,{
@@ -906,10 +956,30 @@
"constname": "k_pch_audio_OffRecordDevice_String","consttype": "const char *const", "constval": "offRecordDevice"}
,{
"constname": "k_pch_audio_VIVEHDMIGain","consttype": "const char *const", "constval": "viveHDMIGain"}
,{
"constname": "k_pch_Power_Section","consttype": "const char *const", "constval": "power"}
,{
"constname": "k_pch_Power_PowerOffOnExit_Bool","consttype": "const char *const", "constval": "powerOffOnExit"}
,{
"constname": "k_pch_Power_TurnOffScreensTimeout_Float","consttype": "const char *const", "constval": "turnOffScreensTimeout"}
,{
"constname": "k_pch_Power_TurnOffControllersTimeout_Float","consttype": "const char *const", "constval": "turnOffControllersTimeout"}
,{
"constname": "k_pch_Power_ReturnToWatchdogTimeout_Float","consttype": "const char *const", "constval": "returnToWatchdogTimeout"}
,{
"constname": "k_pch_Power_AutoLaunchSteamVROnButtonPress","consttype": "const char *const", "constval": "autoLaunchSteamVROnButtonPress"}
,{
"constname": "k_pch_Dashboard_Section","consttype": "const char *const", "constval": "dashboard"}
,{
"constname": "k_pch_Dashboard_EnableDashboard_Bool","consttype": "const char *const", "constval": "enableDashboard"}
,{
"constname": "k_pch_Dashboard_ArcadeMode_Bool","consttype": "const char *const", "constval": "arcadeMode"}
,{
"constname": "k_pch_modelskin_Section","consttype": "const char *const", "constval": "modelskins"}
,{
"constname": "IVRScreenshots_Version","consttype": "const char *const", "constval": "IVRScreenshots_001"}
,{
"constname": "IVRResources_Version","consttype": "const char *const", "constval": "IVRResources_001"}
],
"structs":[{"struct": "vr::HmdMatrix34_t","fields": [
{ "fieldname": "m", "fieldtype": "float [3][4]"}]}
@@ -958,6 +1028,17 @@
{ "fieldname": "vMin", "fieldtype": "float"},
{ "fieldname": "uMax", "fieldtype": "float"},
{ "fieldname": "vMax", "fieldtype": "float"}]}
,{"struct": "vr::VulkanData_t","fields": [
{ "fieldname": "m_nImage", "fieldtype": "uint64_t"},
{ "fieldname": "m_pDevice", "fieldtype": "struct VkDevice_T *"},
{ "fieldname": "m_pPhysicalDevice", "fieldtype": "struct VkPhysicalDevice_T *"},
{ "fieldname": "m_pInstance", "fieldtype": "struct VkInstance_T *"},
{ "fieldname": "m_pQueue", "fieldtype": "struct VkQueue_T *"},
{ "fieldname": "m_nQueueFamilyIndex", "fieldtype": "uint32_t"},
{ "fieldname": "m_nWidth", "fieldtype": "uint32_t"},
{ "fieldname": "m_nHeight", "fieldtype": "uint32_t"},
{ "fieldname": "m_nFormat", "fieldtype": "uint32_t"},
{ "fieldname": "m_nSampleCount", "fieldtype": "uint32_t"}]}
,{"struct": "vr::VREvent_Controller_t","fields": [
{ "fieldname": "button", "fieldtype": "uint32_t"}]}
,{"struct": "vr::VREvent_Mouse_t","fields": [
@@ -1004,6 +1085,14 @@
,{"struct": "vr::VREvent_Screenshot_t","fields": [
{ "fieldname": "handle", "fieldtype": "uint32_t"},
{ "fieldname": "type", "fieldtype": "uint32_t"}]}
,{"struct": "vr::VREvent_ScreenshotProgress_t","fields": [
{ "fieldname": "progress", "fieldtype": "float"}]}
,{"struct": "vr::VREvent_ApplicationLaunch_t","fields": [
{ "fieldname": "pid", "fieldtype": "uint32_t"},
{ "fieldname": "unArgsHandle", "fieldtype": "uint32_t"}]}
,{"struct": "vr::VREvent_EditingCameraSurface_t","fields": [
{ "fieldname": "overlayHandle", "fieldtype": "uint64_t"},
{ "fieldname": "nVisualMode", "fieldtype": "uint32_t"}]}
,{"struct": "vr::(anonymous)","fields": [
{ "fieldname": "reserved", "fieldtype": "struct vr::VREvent_Reserved_t"},
{ "fieldname": "controller", "fieldtype": "struct vr::VREvent_Controller_t"},
@@ -1019,7 +1108,10 @@
{ "fieldname": "performanceTest", "fieldtype": "struct vr::VREvent_PerformanceTest_t"},
{ "fieldname": "touchPadMove", "fieldtype": "struct vr::VREvent_TouchPadMove_t"},
{ "fieldname": "seatedZeroPoseReset", "fieldtype": "struct vr::VREvent_SeatedZeroPoseReset_t"},
{ "fieldname": "screenshot", "fieldtype": "struct vr::VREvent_Screenshot_t"}]}
{ "fieldname": "screenshot", "fieldtype": "struct vr::VREvent_Screenshot_t"},
{ "fieldname": "screenshotProgress", "fieldtype": "struct vr::VREvent_ScreenshotProgress_t"},
{ "fieldname": "applicationLaunch", "fieldtype": "struct vr::VREvent_ApplicationLaunch_t"},
{ "fieldname": "cameraSurface", "fieldtype": "struct vr::VREvent_EditingCameraSurface_t"}]}
,{"struct": "vr::VREvent_t","fields": [
{ "fieldname": "eventType", "fieldtype": "uint32_t"},
{ "fieldname": "trackedDeviceIndex", "fieldtype": "TrackedDeviceIndex_t"},
@@ -1066,8 +1158,10 @@
{ "fieldname": "m_nFrameIndex", "fieldtype": "uint32_t"},
{ "fieldname": "m_nNumFramePresents", "fieldtype": "uint32_t"},
{ "fieldname": "m_nNumDroppedFrames", "fieldtype": "uint32_t"},
{ "fieldname": "m_nReprojectionFlags", "fieldtype": "uint32_t"},
{ "fieldname": "m_flSystemTimeInSeconds", "fieldtype": "double"},
{ "fieldname": "m_flSceneRenderGpuMs", "fieldtype": "float"},
{ "fieldname": "m_flPreSubmitGpuMs", "fieldtype": "float"},
{ "fieldname": "m_flPostSubmitGpuMs", "fieldtype": "float"},
{ "fieldname": "m_flTotalRenderGpuMs", "fieldtype": "float"},
{ "fieldname": "m_flCompositorRenderGpuMs", "fieldtype": "float"},
{ "fieldname": "m_flCompositorRenderCpuMs", "fieldtype": "float"},
@@ -1082,9 +1176,7 @@
{ "fieldname": "m_flCompositorUpdateStartMs", "fieldtype": "float"},
{ "fieldname": "m_flCompositorUpdateEndMs", "fieldtype": "float"},
{ "fieldname": "m_flCompositorRenderStartMs", "fieldtype": "float"},
{ "fieldname": "m_HmdPose", "fieldtype": "vr::TrackedDevicePose_t"},
{ "fieldname": "m_nFidelityLevel", "fieldtype": "int32_t"},
{ "fieldname": "m_nReprojectionFlags", "fieldtype": "uint32_t"}]}
{ "fieldname": "m_HmdPose", "fieldtype": "vr::TrackedDevicePose_t"}]}
,{"struct": "vr::Compositor_CumulativeStats","fields": [
{ "fieldname": "m_nPid", "fieldtype": "uint32_t"},
{ "fieldname": "m_nNumFramePresents", "fieldtype": "uint32_t"},
@@ -1141,6 +1233,7 @@
{ "fieldname": "m_pVRChaperoneSetup", "fieldtype": "class vr::IVRChaperoneSetup *"},
{ "fieldname": "m_pVRCompositor", "fieldtype": "class vr::IVRCompositor *"},
{ "fieldname": "m_pVROverlay", "fieldtype": "class vr::IVROverlay *"},
{ "fieldname": "m_pVRResources", "fieldtype": "class vr::IVRResources *"},
{ "fieldname": "m_pVRRenderModels", "fieldtype": "class vr::IVRRenderModels *"},
{ "fieldname": "m_pVRExtendedDisplay", "fieldtype": "class vr::IVRExtendedDisplay *"},
{ "fieldname": "m_pVRSettings", "fieldtype": "class vr::IVRSettings *"},
@@ -1630,6 +1723,52 @@
{ "paramname": "nFrameHeaderSize" ,"paramtype": "uint32_t"}
]
}
,{
"classname": "vr::IVRTrackedCamera",
"methodname": "GetVideoStreamTextureSize",
"returntype": "vr::EVRTrackedCameraError",
"params": [
{ "paramname": "nDeviceIndex" ,"paramtype": "vr::TrackedDeviceIndex_t"},
{ "paramname": "eFrameType" ,"paramtype": "vr::EVRTrackedCameraFrameType"},
{ "paramname": "pTextureBounds" ,"paramtype": "vr::VRTextureBounds_t *"},
{ "paramname": "pnWidth" ,"paramtype": "uint32_t *"},
{ "paramname": "pnHeight" ,"paramtype": "uint32_t *"}
]
}
,{
"classname": "vr::IVRTrackedCamera",
"methodname": "GetVideoStreamTextureD3D11",
"returntype": "vr::EVRTrackedCameraError",
"params": [
{ "paramname": "hTrackedCamera" ,"paramtype": "vr::TrackedCameraHandle_t"},
{ "paramname": "eFrameType" ,"paramtype": "vr::EVRTrackedCameraFrameType"},
{ "paramname": "pD3D11DeviceOrResource" ,"paramtype": "void *"},
{ "paramname": "ppD3D11ShaderResourceView" ,"paramtype": "void **"},
{ "paramname": "pFrameHeader" ,"paramtype": "vr::CameraVideoStreamFrameHeader_t *"},
{ "paramname": "nFrameHeaderSize" ,"paramtype": "uint32_t"}
]
}
,{
"classname": "vr::IVRTrackedCamera",
"methodname": "GetVideoStreamTextureGL",
"returntype": "vr::EVRTrackedCameraError",
"params": [
{ "paramname": "hTrackedCamera" ,"paramtype": "vr::TrackedCameraHandle_t"},
{ "paramname": "eFrameType" ,"paramtype": "vr::EVRTrackedCameraFrameType"},
{ "paramname": "pglTextureId" ,"paramtype": "vr::glUInt_t *"},
{ "paramname": "pFrameHeader" ,"paramtype": "vr::CameraVideoStreamFrameHeader_t *"},
{ "paramname": "nFrameHeaderSize" ,"paramtype": "uint32_t"}
]
}
,{
"classname": "vr::IVRTrackedCamera",
"methodname": "ReleaseVideoStreamTextureGL",
"returntype": "vr::EVRTrackedCameraError",
"params": [
{ "paramname": "hTrackedCamera" ,"paramtype": "vr::TrackedCameraHandle_t"},
{ "paramname": "glTextureId" ,"paramtype": "vr::glUInt_t"}
]
}
,{
"classname": "vr::IVRApplications",
"methodname": "AddApplicationManifest",
@@ -1666,7 +1805,7 @@
"returntype": "vr::EVRApplicationError",
"params": [
{ "paramname": "unApplicationIndex" ,"paramtype": "uint32_t"},
{ "paramname": "pchAppKeyBuffer" ,"paramtype": "char *"},
{ "paramname": "pchAppKeyBuffer" ,"out_string": " " ,"paramtype": "char *"},
{ "paramname": "unAppKeyBufferLen" ,"paramtype": "uint32_t"}
]
}
@@ -1699,6 +1838,15 @@
{ "paramname": "unKeys" ,"paramtype": "uint32_t"}
]
}
,{
"classname": "vr::IVRApplications",
"methodname": "LaunchApplicationFromMimeType",
"returntype": "vr::EVRApplicationError",
"params": [
{ "paramname": "pchMimeType" ,"paramtype": "const char *"},
{ "paramname": "pchArgs" ,"paramtype": "const char *"}
]
}
,{
"classname": "vr::IVRApplications",
"methodname": "LaunchDashboardOverlay",
@@ -1747,7 +1895,7 @@
"params": [
{ "paramname": "pchAppKey" ,"paramtype": "const char *"},
{ "paramname": "eProperty" ,"paramtype": "vr::EVRApplicationProperty"},
{ "paramname": "pchPropertyValueBuffer" ,"paramtype": "char *"},
{ "paramname": "pchPropertyValueBuffer" ,"out_string": " " ,"paramtype": "char *"},
{ "paramname": "unPropertyValueBufferLen" ,"paramtype": "uint32_t"},
{ "paramname": "peError" ,"paramtype": "vr::EVRApplicationError *"}
]
@@ -1789,6 +1937,55 @@
{ "paramname": "pchAppKey" ,"paramtype": "const char *"}
]
}
,{
"classname": "vr::IVRApplications",
"methodname": "SetDefaultApplicationForMimeType",
"returntype": "vr::EVRApplicationError",
"params": [
{ "paramname": "pchAppKey" ,"paramtype": "const char *"},
{ "paramname": "pchMimeType" ,"paramtype": "const char *"}
]
}
,{
"classname": "vr::IVRApplications",
"methodname": "GetDefaultApplicationForMimeType",
"returntype": "bool",
"params": [
{ "paramname": "pchMimeType" ,"paramtype": "const char *"},
{ "paramname": "pchAppKeyBuffer" ,"paramtype": "char *"},
{ "paramname": "unAppKeyBufferLen" ,"paramtype": "uint32_t"}
]
}
,{
"classname": "vr::IVRApplications",
"methodname": "GetApplicationSupportedMimeTypes",
"returntype": "bool",
"params": [
{ "paramname": "pchAppKey" ,"paramtype": "const char *"},
{ "paramname": "pchMimeTypesBuffer" ,"paramtype": "char *"},
{ "paramname": "unMimeTypesBuffer" ,"paramtype": "uint32_t"}
]
}
,{
"classname": "vr::IVRApplications",
"methodname": "GetApplicationsThatSupportMimeType",
"returntype": "uint32_t",
"params": [
{ "paramname": "pchMimeType" ,"paramtype": "const char *"},
{ "paramname": "pchAppKeysThatSupportBuffer" ,"paramtype": "char *"},
{ "paramname": "unAppKeysThatSupportBuffer" ,"paramtype": "uint32_t"}
]
}
,{
"classname": "vr::IVRApplications",
"methodname": "GetApplicationLaunchArguments",
"returntype": "uint32_t",
"params": [
{ "paramname": "unHandle" ,"paramtype": "uint32_t"},
{ "paramname": "pchArgs" ,"paramtype": "char *"},
{ "paramname": "unArgs" ,"paramtype": "uint32_t"}
]
}
,{
"classname": "vr::IVRApplications",
"methodname": "GetStartingApplication",
@@ -2267,21 +2464,6 @@
{ "paramname": "bSuspend" ,"paramtype": "bool"}
]
}
,{
"classname": "vr::IVRCompositor",
"methodname": "RequestScreenshot",
"returntype": "vr::EVRCompositorError",
"params": [
{ "paramname": "type" ,"paramtype": "vr::EVRScreenshotType"},
{ "paramname": "pchDestinationFileName" ,"paramtype": "const char *"},
{ "paramname": "pchVRDestinationFileName" ,"paramtype": "const char *"}
]
}
,{
"classname": "vr::IVRCompositor",
"methodname": "GetCurrentScreenshotType",
"returntype": "vr::EVRScreenshotType"
}
,{
"classname": "vr::IVRCompositor",
"methodname": "GetMirrorTextureD3D11",
@@ -2486,6 +2668,42 @@
{ "paramname": "pfAlpha" ,"paramtype": "float *"}
]
}
,{
"classname": "vr::IVROverlay",
"methodname": "SetOverlayTexelAspect",
"returntype": "vr::EVROverlayError",
"params": [
{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"},
{ "paramname": "fTexelAspect" ,"paramtype": "float"}
]
}
,{
"classname": "vr::IVROverlay",
"methodname": "GetOverlayTexelAspect",
"returntype": "vr::EVROverlayError",
"params": [
{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"},
{ "paramname": "pfTexelAspect" ,"paramtype": "float *"}
]
}
,{
"classname": "vr::IVROverlay",
"methodname": "SetOverlaySortOrder",
"returntype": "vr::EVROverlayError",
"params": [
{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"},
{ "paramname": "unSortOrder" ,"paramtype": "uint32_t"}
]
}
,{
"classname": "vr::IVROverlay",
"methodname": "GetOverlaySortOrder",
"returntype": "vr::EVROverlayError",
"params": [
{ "paramname": "ulOverlayHandle" ,"paramtype": "vr::VROverlayHandle_t"},
{ "paramname": "punSortOrder" ,"paramtype": "uint32_t *"}
]
}
,{
"classname": "vr::IVROverlay",
"methodname": "SetOverlayWidthInMeters",
@@ -3163,17 +3381,6 @@
{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"}
]
}
,{
"classname": "vr::IVRSettings",
"methodname": "GetBool",
"returntype": "bool",
"params": [
{ "paramname": "pchSection" ,"paramtype": "const char *"},
{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"},
{ "paramname": "bDefaultValue" ,"paramtype": "bool"},
{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"}
]
}
,{
"classname": "vr::IVRSettings",
"methodname": "SetBool",
@@ -3185,17 +3392,6 @@
{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"}
]
}
,{
"classname": "vr::IVRSettings",
"methodname": "GetInt32",
"returntype": "int32_t",
"params": [
{ "paramname": "pchSection" ,"paramtype": "const char *"},
{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"},
{ "paramname": "nDefaultValue" ,"paramtype": "int32_t"},
{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"}
]
}
,{
"classname": "vr::IVRSettings",
"methodname": "SetInt32",
@@ -3207,17 +3403,6 @@
{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"}
]
}
,{
"classname": "vr::IVRSettings",
"methodname": "GetFloat",
"returntype": "float",
"params": [
{ "paramname": "pchSection" ,"paramtype": "const char *"},
{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"},
{ "paramname": "flDefaultValue" ,"paramtype": "float"},
{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"}
]
}
,{
"classname": "vr::IVRSettings",
"methodname": "SetFloat",
@@ -3229,19 +3414,6 @@
{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"}
]
}
,{
"classname": "vr::IVRSettings",
"methodname": "GetString",
"returntype": "void",
"params": [
{ "paramname": "pchSection" ,"paramtype": "const char *"},
{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"},
{ "paramname": "pchValue" ,"paramtype": "char *"},
{ "paramname": "unValueLen" ,"paramtype": "uint32_t"},
{ "paramname": "pchDefaultValue" ,"paramtype": "const char *"},
{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"}
]
}
,{
"classname": "vr::IVRSettings",
"methodname": "SetString",
@@ -3253,6 +3425,48 @@
{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"}
]
}
,{
"classname": "vr::IVRSettings",
"methodname": "GetBool",
"returntype": "bool",
"params": [
{ "paramname": "pchSection" ,"paramtype": "const char *"},
{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"},
{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"}
]
}
,{
"classname": "vr::IVRSettings",
"methodname": "GetInt32",
"returntype": "int32_t",
"params": [
{ "paramname": "pchSection" ,"paramtype": "const char *"},
{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"},
{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"}
]
}
,{
"classname": "vr::IVRSettings",
"methodname": "GetFloat",
"returntype": "float",
"params": [
{ "paramname": "pchSection" ,"paramtype": "const char *"},
{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"},
{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"}
]
}
,{
"classname": "vr::IVRSettings",
"methodname": "GetString",
"returntype": "void",
"params": [
{ "paramname": "pchSection" ,"paramtype": "const char *"},
{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"},
{ "paramname": "pchValue" ,"out_string": " " ,"paramtype": "char *"},
{ "paramname": "unValueLen" ,"paramtype": "uint32_t"},
{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"}
]
}
,{
"classname": "vr::IVRSettings",
"methodname": "RemoveSection",
@@ -3343,5 +3557,26 @@
{ "paramname": "pchSourceVRFilename" ,"paramtype": "const char *"}
]
}
,{
"classname": "vr::IVRResources",
"methodname": "LoadSharedResource",
"returntype": "uint32_t",
"params": [
{ "paramname": "pchResourceName" ,"paramtype": "const char *"},
{ "paramname": "pchBuffer" ,"paramtype": "char *"},
{ "paramname": "unBufferLen" ,"paramtype": "uint32_t"}
]
}
,{
"classname": "vr::IVRResources",
"methodname": "GetResourceFullPath",
"returntype": "uint32_t",
"params": [
{ "paramname": "pchResourceName" ,"paramtype": "const char *"},
{ "paramname": "pchResourceTypeDirectory" ,"paramtype": "const char *"},
{ "paramname": "pchPathBuffer" ,"paramtype": "char *"},
{ "paramname": "unBufferLen" ,"paramtype": "uint32_t"}
]
}
]
}

View File

@@ -28,7 +28,7 @@
#else
#define S_API extern "C" __declspec( dllimport )
#endif // OPENVR_API_EXPORTS
#elif defined( GNUC )
#elif defined( __GNUC__ )
#if defined( OPENVR_API_EXPORTS )
#define S_API EXTERN_C __attribute__ ((visibility("default")))
#else
@@ -65,14 +65,16 @@ static const char * IVRSystem_Version = "IVRSystem_012";
static const char * IVRExtendedDisplay_Version = "IVRExtendedDisplay_001";
static const char * IVRTrackedCamera_Version = "IVRTrackedCamera_003";
static const unsigned int k_unMaxApplicationKeyLength = 128;
static const char * IVRApplications_Version = "IVRApplications_005";
static const char * k_pch_MimeType_HomeApp = "vr/home";
static const char * k_pch_MimeType_GameTheater = "vr/game_theater";
static const char * IVRApplications_Version = "IVRApplications_006";
static const char * IVRChaperone_Version = "IVRChaperone_003";
static const char * IVRChaperoneSetup_Version = "IVRChaperoneSetup_005";
static const char * IVRCompositor_Version = "IVRCompositor_015";
static const char * IVRCompositor_Version = "IVRCompositor_016";
static const unsigned int k_unVROverlayMaxKeyLength = 128;
static const unsigned int k_unVROverlayMaxNameLength = 128;
static const unsigned int k_unMaxOverlayCount = 32;
static const char * IVROverlay_Version = "IVROverlay_012";
static const unsigned int k_unMaxOverlayCount = 64;
static const char * IVROverlay_Version = "IVROverlay_013";
static const char * k_pch_Controller_Component_GDC2015 = "gdc2015";
static const char * k_pch_Controller_Component_Base = "base";
static const char * k_pch_Controller_Component_Tip = "tip";
@@ -82,7 +84,7 @@ static const char * IVRRenderModels_Version = "IVRRenderModels_005";
static const unsigned int k_unNotificationTextMaxSize = 256;
static const char * IVRNotifications_Version = "IVRNotifications_002";
static const unsigned int k_unMaxSettingsKeyLength = 128;
static const char * IVRSettings_Version = "IVRSettings_001";
static const char * IVRSettings_Version = "IVRSettings_002";
static const char * k_pch_SteamVR_Section = "steamvr";
static const char * k_pch_SteamVR_RequireHmd_String = "requireHmd";
static const char * k_pch_SteamVR_ForcedDriverKey_String = "forcedDriver";
@@ -103,9 +105,6 @@ static const char * k_pch_SteamVR_GridColor_String = "gridColor";
static const char * k_pch_SteamVR_PlayAreaColor_String = "playAreaColor";
static const char * k_pch_SteamVR_ShowStage_Bool = "showStage";
static const char * k_pch_SteamVR_ActivateMultipleDrivers_Bool = "activateMultipleDrivers";
static const char * k_pch_SteamVR_PowerOffOnExit_Bool = "powerOffOnExit";
static const char * k_pch_SteamVR_StandbyAppRunningTimeout_Float = "standbyAppRunningTimeout";
static const char * k_pch_SteamVR_StandbyNoAppTimeout_Float = "standbyNoAppTimeout";
static const char * k_pch_SteamVR_DirectMode_Bool = "directMode";
static const char * k_pch_SteamVR_DirectModeEdidVid_Int32 = "directModeEdidVid";
static const char * k_pch_SteamVR_DirectModeEdidPid_Int32 = "directModeEdidPid";
@@ -119,14 +118,17 @@ static const char * k_pch_SteamVR_ForceReprojection_Bool = "forceReprojection";
static const char * k_pch_SteamVR_ForceFadeOnBadTracking_Bool = "forceFadeOnBadTracking";
static const char * k_pch_SteamVR_DefaultMirrorView_Int32 = "defaultMirrorView";
static const char * k_pch_SteamVR_ShowMirrorView_Bool = "showMirrorView";
static const char * k_pch_SteamVR_MirrorViewGeometry_String = "mirrorViewGeometry";
static const char * k_pch_SteamVR_StartMonitorFromAppLaunch = "startMonitorFromAppLaunch";
static const char * k_pch_SteamVR_EnableHomeApp = "enableHomeApp";
static const char * k_pch_SteamVR_SetInitialDefaultHomeApp = "setInitialDefaultHomeApp";
static const char * k_pch_SteamVR_CycleBackgroundImageTimeSec_Int32 = "CycleBackgroundImageTimeSec";
static const char * k_pch_SteamVR_RetailDemo_Bool = "retailDemo";
static const char * k_pch_Lighthouse_Section = "driver_lighthouse";
static const char * k_pch_Lighthouse_DisableIMU_Bool = "disableimu";
static const char * k_pch_Lighthouse_UseDisambiguation_String = "usedisambiguation";
static const char * k_pch_Lighthouse_DisambiguationDebug_Int32 = "disambiguationdebug";
static const char * k_pch_Lighthouse_PrimaryBasestation_Int32 = "primarybasestation";
static const char * k_pch_Lighthouse_LighthouseName_String = "lighthousename";
static const char * k_pch_Lighthouse_MaxIncidenceAngleDegrees_Float = "maxincidenceangledegrees";
static const char * k_pch_Lighthouse_UseLighthouseDirect_Bool = "uselighthousedirect";
static const char * k_pch_Lighthouse_DBHistory_Bool = "dbhistory";
static const char * k_pch_Null_Section = "driver_null";
static const char * k_pch_Null_EnableNullDriver_Bool = "enable";
@@ -142,7 +144,8 @@ static const char * k_pch_Null_SecondsFromVsyncToPhotons_Float = "secondsFromVsy
static const char * k_pch_Null_DisplayFrequency_Float = "displayFrequency";
static const char * k_pch_UserInterface_Section = "userinterface";
static const char * k_pch_UserInterface_StatusAlwaysOnTop_Bool = "StatusAlwaysOnTop";
static const char * k_pch_UserInterface_EnableScreenshots_Bool = "EnableScreenshots";
static const char * k_pch_UserInterface_Screenshots_Bool = "screenshots";
static const char * k_pch_UserInterface_ScreenshotType_Int = "screenshotType";
static const char * k_pch_Notifications_Section = "notifications";
static const char * k_pch_Notifications_DoNotDisturb_Bool = "DoNotDisturb";
static const char * k_pch_Keyboard_Section = "keyboard";
@@ -179,6 +182,7 @@ static const char * k_pch_Camera_BoundsColorGammaR_Int32 = "cameraBoundsColorGam
static const char * k_pch_Camera_BoundsColorGammaG_Int32 = "cameraBoundsColorGammaG";
static const char * k_pch_Camera_BoundsColorGammaB_Int32 = "cameraBoundsColorGammaB";
static const char * k_pch_Camera_BoundsColorGammaA_Int32 = "cameraBoundsColorGammaA";
static const char * k_pch_Camera_BoundsStrength_Int32 = "cameraBoundsStrength";
static const char * k_pch_audio_Section = "audio";
static const char * k_pch_audio_OnPlaybackDevice_String = "onPlaybackDevice";
static const char * k_pch_audio_OnRecordDevice_String = "onRecordDevice";
@@ -186,8 +190,18 @@ static const char * k_pch_audio_OnPlaybackMirrorDevice_String = "onPlaybackMirro
static const char * k_pch_audio_OffPlaybackDevice_String = "offPlaybackDevice";
static const char * k_pch_audio_OffRecordDevice_String = "offRecordDevice";
static const char * k_pch_audio_VIVEHDMIGain = "viveHDMIGain";
static const char * k_pch_Power_Section = "power";
static const char * k_pch_Power_PowerOffOnExit_Bool = "powerOffOnExit";
static const char * k_pch_Power_TurnOffScreensTimeout_Float = "turnOffScreensTimeout";
static const char * k_pch_Power_TurnOffControllersTimeout_Float = "turnOffControllersTimeout";
static const char * k_pch_Power_ReturnToWatchdogTimeout_Float = "returnToWatchdogTimeout";
static const char * k_pch_Power_AutoLaunchSteamVROnButtonPress = "autoLaunchSteamVROnButtonPress";
static const char * k_pch_Dashboard_Section = "dashboard";
static const char * k_pch_Dashboard_EnableDashboard_Bool = "enableDashboard";
static const char * k_pch_Dashboard_ArcadeMode_Bool = "arcadeMode";
static const char * k_pch_modelskin_Section = "modelskins";
static const char * IVRScreenshots_Version = "IVRScreenshots_001";
static const char * IVRResources_Version = "IVRResources_001";
// OpenVR Enums
@@ -225,6 +239,7 @@ typedef enum ETrackedDeviceClass
ETrackedDeviceClass_TrackedDeviceClass_HMD = 1,
ETrackedDeviceClass_TrackedDeviceClass_Controller = 2,
ETrackedDeviceClass_TrackedDeviceClass_TrackingReference = 4,
ETrackedDeviceClass_TrackedDeviceClass_Count = 5,
ETrackedDeviceClass_TrackedDeviceClass_Other = 1000,
} ETrackedDeviceClass;
@@ -321,6 +336,7 @@ typedef enum ETrackedDeviceProperty
ETrackedDeviceProperty_Prop_Axis2Type_Int32 = 3004,
ETrackedDeviceProperty_Prop_Axis3Type_Int32 = 3005,
ETrackedDeviceProperty_Prop_Axis4Type_Int32 = 3006,
ETrackedDeviceProperty_Prop_ControllerRoleHint_Int32 = 3007,
ETrackedDeviceProperty_Prop_FieldOfViewLeftDegrees_Float = 4000,
ETrackedDeviceProperty_Prop_FieldOfViewRightDegrees_Float = 4001,
ETrackedDeviceProperty_Prop_FieldOfViewTopDegrees_Float = 4002,
@@ -328,6 +344,15 @@ typedef enum ETrackedDeviceProperty
ETrackedDeviceProperty_Prop_TrackingRangeMinimumMeters_Float = 4004,
ETrackedDeviceProperty_Prop_TrackingRangeMaximumMeters_Float = 4005,
ETrackedDeviceProperty_Prop_ModeLabel_String = 4006,
ETrackedDeviceProperty_Prop_IconPathName_String = 5000,
ETrackedDeviceProperty_Prop_NamedIconPathDeviceOff_String = 5001,
ETrackedDeviceProperty_Prop_NamedIconPathDeviceSearching_String = 5002,
ETrackedDeviceProperty_Prop_NamedIconPathDeviceSearchingAlert_String = 5003,
ETrackedDeviceProperty_Prop_NamedIconPathDeviceReady_String = 5004,
ETrackedDeviceProperty_Prop_NamedIconPathDeviceReadyAlert_String = 5005,
ETrackedDeviceProperty_Prop_NamedIconPathDeviceNotReady_String = 5006,
ETrackedDeviceProperty_Prop_NamedIconPathDeviceStandby_String = 5007,
ETrackedDeviceProperty_Prop_NamedIconPathDeviceAlertLow_String = 5008,
ETrackedDeviceProperty_Prop_VendorSpecific_Reserved_Start = 10000,
ETrackedDeviceProperty_Prop_VendorSpecific_Reserved_End = 10999,
} ETrackedDeviceProperty;
@@ -351,6 +376,7 @@ typedef enum EVRSubmitFlags
EVRSubmitFlags_Submit_Default = 0,
EVRSubmitFlags_Submit_LensDistortionAlreadyApplied = 1,
EVRSubmitFlags_Submit_GlRenderBuffer = 2,
EVRSubmitFlags_Submit_VulkanTexture = 4,
} EVRSubmitFlags;
typedef enum EVRState
@@ -363,6 +389,7 @@ typedef enum EVRState
EVRState_VRState_Ready_Alert = 4,
EVRState_VRState_NotReady = 5,
EVRState_VRState_Standby = 6,
EVRState_VRState_Ready_Alert_Low = 7,
} EVRState;
typedef enum EVREventType
@@ -377,6 +404,8 @@ typedef enum EVREventType
EVREventType_VREvent_EnterStandbyMode = 106,
EVREventType_VREvent_LeaveStandbyMode = 107,
EVREventType_VREvent_TrackedDeviceRoleChanged = 108,
EVREventType_VREvent_WatchdogWakeUpRequested = 109,
EVREventType_VREvent_LensDistortionChanged = 110,
EVREventType_VREvent_ButtonPress = 200,
EVREventType_VREvent_ButtonUnpress = 201,
EVREventType_VREvent_ButtonTouch = 202,
@@ -388,6 +417,7 @@ typedef enum EVREventType
EVREventType_VREvent_FocusLeave = 304,
EVREventType_VREvent_Scroll = 305,
EVREventType_VREvent_TouchPadMove = 306,
EVREventType_VREvent_OverlayFocusChanged = 307,
EVREventType_VREvent_InputFocusCaptured = 400,
EVREventType_VREvent_InputFocusReleased = 401,
EVREventType_VREvent_SceneFocusLost = 402,
@@ -416,10 +446,12 @@ typedef enum EVREventType
EVREventType_VREvent_DashboardGuideButtonUp = 515,
EVREventType_VREvent_ScreenshotTriggered = 516,
EVREventType_VREvent_ImageFailed = 517,
EVREventType_VREvent_DashboardOverlayCreated = 518,
EVREventType_VREvent_RequestScreenshot = 520,
EVREventType_VREvent_ScreenshotTaken = 521,
EVREventType_VREvent_ScreenshotFailed = 522,
EVREventType_VREvent_SubmitScreenshotToDashboard = 523,
EVREventType_VREvent_ScreenshotProgressToDashboard = 524,
EVREventType_VREvent_Notification_Shown = 600,
EVREventType_VREvent_Notification_Hidden = 601,
EVREventType_VREvent_Notification_BeginInteraction = 602,
@@ -440,6 +472,7 @@ typedef enum EVREventType
EVREventType_VREvent_ReprojectionSettingHasChanged = 852,
EVREventType_VREvent_ModelSkinSettingsHaveChanged = 853,
EVREventType_VREvent_EnvironmentSettingsHaveChanged = 854,
EVREventType_VREvent_PowerSettingsHaveChanged = 855,
EVREventType_VREvent_StatusUpdate = 900,
EVREventType_VREvent_MCImageUpdated = 1000,
EVREventType_VREvent_FirmwareUpdateStarted = 1100,
@@ -451,6 +484,7 @@ typedef enum EVREventType
EVREventType_VREvent_ApplicationTransitionAborted = 1301,
EVREventType_VREvent_ApplicationTransitionNewAppStarted = 1302,
EVREventType_VREvent_ApplicationListUpdated = 1303,
EVREventType_VREvent_ApplicationMimeTypeLoad = 1304,
EVREventType_VREvent_Compositor_MirrorWindowShown = 1400,
EVREventType_VREvent_Compositor_MirrorWindowHidden = 1401,
EVREventType_VREvent_Compositor_ChaperoneBoundsShown = 1410,
@@ -459,6 +493,7 @@ typedef enum EVREventType
EVREventType_VREvent_TrackedCamera_StopVideoStream = 1501,
EVREventType_VREvent_TrackedCamera_PauseVideoStream = 1502,
EVREventType_VREvent_TrackedCamera_ResumeVideoStream = 1503,
EVREventType_VREvent_TrackedCamera_EditingSurface = 1550,
EVREventType_VREvent_PerformanceTest_EnableCapture = 1600,
EVREventType_VREvent_PerformanceTest_DisableCapture = 1601,
EVREventType_VREvent_PerformanceTest_FidelityLevel = 1602,
@@ -485,6 +520,7 @@ typedef enum EVRButtonId
EVRButtonId_k_EButton_DPad_Right = 5,
EVRButtonId_k_EButton_DPad_Down = 6,
EVRButtonId_k_EButton_A = 7,
EVRButtonId_k_EButton_ProximitySensor = 31,
EVRButtonId_k_EButton_Axis0 = 32,
EVRButtonId_k_EButton_Axis1 = 33,
EVRButtonId_k_EButton_Axis2 = 34,
@@ -546,7 +582,7 @@ typedef enum EVROverlayError
EVROverlayError_VROverlayError_RequestFailed = 23,
EVROverlayError_VROverlayError_InvalidTexture = 24,
EVROverlayError_VROverlayError_UnableToLoadFile = 25,
EVROverlayError_VROVerlayError_KeyboardAlreadyInUse = 26,
EVROverlayError_VROverlayError_KeyboardAlreadyInUse = 26,
EVROverlayError_VROverlayError_NoNeighbor = 27,
} EVROverlayError;
@@ -558,6 +594,8 @@ typedef enum EVRApplicationType
EVRApplicationType_VRApplication_Background = 3,
EVRApplicationType_VRApplication_Utility = 4,
EVRApplicationType_VRApplication_VRMonitor = 5,
EVRApplicationType_VRApplication_SteamWatchdog = 6,
EVRApplicationType_VRApplication_Max = 7,
} EVRApplicationType;
typedef enum EVRFirmwareError
@@ -605,6 +643,14 @@ typedef enum EVRInitError
EVRInitError_VRInitError_Init_NotSupportedWithCompositor = 122,
EVRInitError_VRInitError_Init_NotAvailableToUtilityApps = 123,
EVRInitError_VRInitError_Init_Internal = 124,
EVRInitError_VRInitError_Init_HmdDriverIdIsNone = 125,
EVRInitError_VRInitError_Init_HmdNotFoundPresenceFailed = 126,
EVRInitError_VRInitError_Init_VRMonitorNotFound = 127,
EVRInitError_VRInitError_Init_VRMonitorStartupFailed = 128,
EVRInitError_VRInitError_Init_LowPowerWatchdogNotSupported = 129,
EVRInitError_VRInitError_Init_InvalidApplicationType = 130,
EVRInitError_VRInitError_Init_NotAvailableToWatchdogApps = 131,
EVRInitError_VRInitError_Init_WatchdogDisabledInSettings = 132,
EVRInitError_VRInitError_Driver_Failed = 200,
EVRInitError_VRInitError_Driver_Unknown = 201,
EVRInitError_VRInitError_Driver_HmdUnknown = 202,
@@ -614,12 +660,18 @@ typedef enum EVRInitError
EVRInitError_VRInitError_Driver_NotCalibrated = 206,
EVRInitError_VRInitError_Driver_CalibrationInvalid = 207,
EVRInitError_VRInitError_Driver_HmdDisplayNotFound = 208,
EVRInitError_VRInitError_Driver_TrackedDeviceInterfaceUnknown = 209,
EVRInitError_VRInitError_Driver_HmdDriverIdOutOfBounds = 211,
EVRInitError_VRInitError_Driver_HmdDisplayMirrored = 212,
EVRInitError_VRInitError_IPC_ServerInitFailed = 300,
EVRInitError_VRInitError_IPC_ConnectFailed = 301,
EVRInitError_VRInitError_IPC_SharedStateInitFailed = 302,
EVRInitError_VRInitError_IPC_CompositorInitFailed = 303,
EVRInitError_VRInitError_IPC_MutexInitFailed = 304,
EVRInitError_VRInitError_IPC_Failed = 305,
EVRInitError_VRInitError_IPC_CompositorConnectFailed = 306,
EVRInitError_VRInitError_IPC_CompositorInvalidConnectResponse = 307,
EVRInitError_VRInitError_IPC_ConnectFailedAfterMultipleAttempts = 308,
EVRInitError_VRInitError_Compositor_Failed = 400,
EVRInitError_VRInitError_Compositor_D3D11HardwareRequired = 401,
EVRInitError_VRInitError_Compositor_FirmwareRequiresUpdate = 402,
@@ -806,6 +858,7 @@ typedef enum VROverlayFlags
VROverlayFlags_SideBySide_Crossed = 11,
VROverlayFlags_Panorama = 12,
VROverlayFlags_StereoPanorama = 13,
VROverlayFlags_SortWithNonSceneOverlays = 14,
} VROverlayFlags;
typedef enum EGamepadTextInputMode
@@ -878,6 +931,8 @@ typedef enum EVRSettingsError
EVRSettingsError_VRSettingsError_IPCFailed = 1,
EVRSettingsError_VRSettingsError_WriteFailed = 2,
EVRSettingsError_VRSettingsError_ReadFailed = 3,
EVRSettingsError_VRSettingsError_JsonParseFailed = 4,
EVRSettingsError_VRSettingsError_UnsetSettingHasNoDefault = 5,
} EVRSettingsError;
typedef enum EVRScreenshotError
@@ -899,6 +954,7 @@ typedef uint64_t VROverlayHandle_t;
typedef void * glSharedTextureHandle_t;
typedef int32_t glInt_t;
typedef uint32_t glUInt_t;
typedef uint64_t SharedTextureHandle_t;
typedef uint32_t TrackedDeviceIndex_t;
typedef uint64_t VROverlayHandle_t;
typedef uint64_t TrackedCameraHandle_t;
@@ -1014,6 +1070,20 @@ typedef struct VRTextureBounds_t
float vMax;
} VRTextureBounds_t;
typedef struct VulkanData_t
{
uint64_t m_nImage;
struct VkDevice_T * m_pDevice; // struct VkDevice_T *
struct VkPhysicalDevice_T * m_pPhysicalDevice; // struct VkPhysicalDevice_T *
struct VkInstance_T * m_pInstance; // struct VkInstance_T *
struct VkQueue_T * m_pQueue; // struct VkQueue_T *
uint32_t m_nQueueFamilyIndex;
uint32_t m_nWidth;
uint32_t m_nHeight;
uint32_t m_nFormat;
uint32_t m_nSampleCount;
} VulkanData_t;
typedef struct VREvent_Controller_t
{
uint32_t button;
@@ -1105,6 +1175,23 @@ typedef struct VREvent_Screenshot_t
uint32_t type;
} VREvent_Screenshot_t;
typedef struct VREvent_ScreenshotProgress_t
{
float progress;
} VREvent_ScreenshotProgress_t;
typedef struct VREvent_ApplicationLaunch_t
{
uint32_t pid;
uint32_t unArgsHandle;
} VREvent_ApplicationLaunch_t;
typedef struct VREvent_EditingCameraSurface_t
{
uint64_t overlayHandle;
uint32_t nVisualMode;
} VREvent_EditingCameraSurface_t;
typedef struct HiddenAreaMesh_t
{
struct HmdVector2_t * pVertexData; // const struct vr::HmdVector2_t *
@@ -1165,8 +1252,10 @@ typedef struct Compositor_FrameTiming
uint32_t m_nFrameIndex;
uint32_t m_nNumFramePresents;
uint32_t m_nNumDroppedFrames;
uint32_t m_nReprojectionFlags;
double m_flSystemTimeInSeconds;
float m_flSceneRenderGpuMs;
float m_flPreSubmitGpuMs;
float m_flPostSubmitGpuMs;
float m_flTotalRenderGpuMs;
float m_flCompositorRenderGpuMs;
float m_flCompositorRenderCpuMs;
@@ -1182,8 +1271,6 @@ typedef struct Compositor_FrameTiming
float m_flCompositorUpdateEndMs;
float m_flCompositorRenderStartMs;
TrackedDevicePose_t m_HmdPose;
int32_t m_nFidelityLevel;
uint32_t m_nReprojectionFlags;
} Compositor_FrameTiming;
typedef struct Compositor_CumulativeStats
@@ -1270,6 +1357,7 @@ typedef struct COpenVRContext
intptr_t m_pVRChaperoneSetup; // class vr::IVRChaperoneSetup *
intptr_t m_pVRCompositor; // class vr::IVRCompositor *
intptr_t m_pVROverlay; // class vr::IVROverlay *
intptr_t m_pVRResources; // class vr::IVRResources *
intptr_t m_pVRRenderModels; // class vr::IVRRenderModels *
intptr_t m_pVRExtendedDisplay; // class vr::IVRExtendedDisplay *
intptr_t m_pVRSettings; // class vr::IVRSettings *
@@ -1375,6 +1463,10 @@ struct VR_IVRTrackedCamera_FnTable
EVRTrackedCameraError (OPENVR_FNTABLE_CALLTYPE *AcquireVideoStreamingService)(TrackedDeviceIndex_t nDeviceIndex, TrackedCameraHandle_t * pHandle);
EVRTrackedCameraError (OPENVR_FNTABLE_CALLTYPE *ReleaseVideoStreamingService)(TrackedCameraHandle_t hTrackedCamera);
EVRTrackedCameraError (OPENVR_FNTABLE_CALLTYPE *GetVideoStreamFrameBuffer)(TrackedCameraHandle_t hTrackedCamera, EVRTrackedCameraFrameType eFrameType, void * pFrameBuffer, uint32_t nFrameBufferSize, CameraVideoStreamFrameHeader_t * pFrameHeader, uint32_t nFrameHeaderSize);
EVRTrackedCameraError (OPENVR_FNTABLE_CALLTYPE *GetVideoStreamTextureSize)(TrackedDeviceIndex_t nDeviceIndex, EVRTrackedCameraFrameType eFrameType, VRTextureBounds_t * pTextureBounds, uint32_t * pnWidth, uint32_t * pnHeight);
EVRTrackedCameraError (OPENVR_FNTABLE_CALLTYPE *GetVideoStreamTextureD3D11)(TrackedCameraHandle_t hTrackedCamera, EVRTrackedCameraFrameType eFrameType, void * pD3D11DeviceOrResource, void ** ppD3D11ShaderResourceView, CameraVideoStreamFrameHeader_t * pFrameHeader, uint32_t nFrameHeaderSize);
EVRTrackedCameraError (OPENVR_FNTABLE_CALLTYPE *GetVideoStreamTextureGL)(TrackedCameraHandle_t hTrackedCamera, EVRTrackedCameraFrameType eFrameType, glUInt_t * pglTextureId, CameraVideoStreamFrameHeader_t * pFrameHeader, uint32_t nFrameHeaderSize);
EVRTrackedCameraError (OPENVR_FNTABLE_CALLTYPE *ReleaseVideoStreamTextureGL)(TrackedCameraHandle_t hTrackedCamera, glUInt_t glTextureId);
};
struct VR_IVRApplications_FnTable
@@ -1387,6 +1479,7 @@ struct VR_IVRApplications_FnTable
EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *GetApplicationKeyByProcessId)(uint32_t unProcessId, char * pchAppKeyBuffer, uint32_t unAppKeyBufferLen);
EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *LaunchApplication)(char * pchAppKey);
EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *LaunchTemplateApplication)(char * pchTemplateAppKey, char * pchNewAppKey, struct AppOverrideKeys_t * pKeys, uint32_t unKeys);
EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *LaunchApplicationFromMimeType)(char * pchMimeType, char * pchArgs);
EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *LaunchDashboardOverlay)(char * pchAppKey);
bool (OPENVR_FNTABLE_CALLTYPE *CancelApplicationLaunch)(char * pchAppKey);
EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *IdentifyApplication)(uint32_t unProcessId, char * pchAppKey);
@@ -1397,6 +1490,11 @@ struct VR_IVRApplications_FnTable
uint64_t (OPENVR_FNTABLE_CALLTYPE *GetApplicationPropertyUint64)(char * pchAppKey, EVRApplicationProperty eProperty, EVRApplicationError * peError);
EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *SetApplicationAutoLaunch)(char * pchAppKey, bool bAutoLaunch);
bool (OPENVR_FNTABLE_CALLTYPE *GetApplicationAutoLaunch)(char * pchAppKey);
EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *SetDefaultApplicationForMimeType)(char * pchAppKey, char * pchMimeType);
bool (OPENVR_FNTABLE_CALLTYPE *GetDefaultApplicationForMimeType)(char * pchMimeType, char * pchAppKeyBuffer, uint32_t unAppKeyBufferLen);
bool (OPENVR_FNTABLE_CALLTYPE *GetApplicationSupportedMimeTypes)(char * pchAppKey, char * pchMimeTypesBuffer, uint32_t unMimeTypesBuffer);
uint32_t (OPENVR_FNTABLE_CALLTYPE *GetApplicationsThatSupportMimeType)(char * pchMimeType, char * pchAppKeysThatSupportBuffer, uint32_t unAppKeysThatSupportBuffer);
uint32_t (OPENVR_FNTABLE_CALLTYPE *GetApplicationLaunchArguments)(uint32_t unHandle, char * pchArgs, uint32_t unArgs);
EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *GetStartingApplication)(char * pchAppKeyBuffer, uint32_t unAppKeyBufferLen);
EVRApplicationTransitionState (OPENVR_FNTABLE_CALLTYPE *GetTransitionState)();
EVRApplicationError (OPENVR_FNTABLE_CALLTYPE *PerformApplicationPrelaunchCheck)(char * pchAppKey);
@@ -1473,8 +1571,6 @@ struct VR_IVRCompositor_FnTable
void (OPENVR_FNTABLE_CALLTYPE *ForceInterleavedReprojectionOn)(bool bOverride);
void (OPENVR_FNTABLE_CALLTYPE *ForceReconnectProcess)();
void (OPENVR_FNTABLE_CALLTYPE *SuspendRendering)(bool bSuspend);
EVRCompositorError (OPENVR_FNTABLE_CALLTYPE *RequestScreenshot)(EVRScreenshotType type, char * pchDestinationFileName, char * pchVRDestinationFileName);
EVRScreenshotType (OPENVR_FNTABLE_CALLTYPE *GetCurrentScreenshotType)();
EVRCompositorError (OPENVR_FNTABLE_CALLTYPE *GetMirrorTextureD3D11)(EVREye eEye, void * pD3D11DeviceOrResource, void ** ppD3D11ShaderResourceView);
EVRCompositorError (OPENVR_FNTABLE_CALLTYPE *GetMirrorTextureGL)(EVREye eEye, glUInt_t * pglTextureId, glSharedTextureHandle_t * pglSharedTextureHandle);
bool (OPENVR_FNTABLE_CALLTYPE *ReleaseSharedGLTexture)(glUInt_t glTextureId, glSharedTextureHandle_t glSharedTextureHandle);
@@ -1501,6 +1597,10 @@ struct VR_IVROverlay_FnTable
EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlayColor)(VROverlayHandle_t ulOverlayHandle, float * pfRed, float * pfGreen, float * pfBlue);
EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayAlpha)(VROverlayHandle_t ulOverlayHandle, float fAlpha);
EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlayAlpha)(VROverlayHandle_t ulOverlayHandle, float * pfAlpha);
EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayTexelAspect)(VROverlayHandle_t ulOverlayHandle, float fTexelAspect);
EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlayTexelAspect)(VROverlayHandle_t ulOverlayHandle, float * pfTexelAspect);
EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlaySortOrder)(VROverlayHandle_t ulOverlayHandle, uint32_t unSortOrder);
EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlaySortOrder)(VROverlayHandle_t ulOverlayHandle, uint32_t * punSortOrder);
EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayWidthInMeters)(VROverlayHandle_t ulOverlayHandle, float fWidthInMeters);
EVROverlayError (OPENVR_FNTABLE_CALLTYPE *GetOverlayWidthInMeters)(VROverlayHandle_t ulOverlayHandle, float * pfWidthInMeters);
EVROverlayError (OPENVR_FNTABLE_CALLTYPE *SetOverlayAutoCurveDistanceRangeInMeters)(VROverlayHandle_t ulOverlayHandle, float fMinDistanceInMeters, float fMaxDistanceInMeters);
@@ -1586,14 +1686,14 @@ struct VR_IVRSettings_FnTable
{
char * (OPENVR_FNTABLE_CALLTYPE *GetSettingsErrorNameFromEnum)(EVRSettingsError eError);
bool (OPENVR_FNTABLE_CALLTYPE *Sync)(bool bForce, EVRSettingsError * peError);
bool (OPENVR_FNTABLE_CALLTYPE *GetBool)(char * pchSection, char * pchSettingsKey, bool bDefaultValue, EVRSettingsError * peError);
void (OPENVR_FNTABLE_CALLTYPE *SetBool)(char * pchSection, char * pchSettingsKey, bool bValue, EVRSettingsError * peError);
int32_t (OPENVR_FNTABLE_CALLTYPE *GetInt32)(char * pchSection, char * pchSettingsKey, int32_t nDefaultValue, EVRSettingsError * peError);
void (OPENVR_FNTABLE_CALLTYPE *SetInt32)(char * pchSection, char * pchSettingsKey, int32_t nValue, EVRSettingsError * peError);
float (OPENVR_FNTABLE_CALLTYPE *GetFloat)(char * pchSection, char * pchSettingsKey, float flDefaultValue, EVRSettingsError * peError);
void (OPENVR_FNTABLE_CALLTYPE *SetFloat)(char * pchSection, char * pchSettingsKey, float flValue, EVRSettingsError * peError);
void (OPENVR_FNTABLE_CALLTYPE *GetString)(char * pchSection, char * pchSettingsKey, char * pchValue, uint32_t unValueLen, char * pchDefaultValue, EVRSettingsError * peError);
void (OPENVR_FNTABLE_CALLTYPE *SetString)(char * pchSection, char * pchSettingsKey, char * pchValue, EVRSettingsError * peError);
bool (OPENVR_FNTABLE_CALLTYPE *GetBool)(char * pchSection, char * pchSettingsKey, EVRSettingsError * peError);
int32_t (OPENVR_FNTABLE_CALLTYPE *GetInt32)(char * pchSection, char * pchSettingsKey, EVRSettingsError * peError);
float (OPENVR_FNTABLE_CALLTYPE *GetFloat)(char * pchSection, char * pchSettingsKey, EVRSettingsError * peError);
void (OPENVR_FNTABLE_CALLTYPE *GetString)(char * pchSection, char * pchSettingsKey, char * pchValue, uint32_t unValueLen, EVRSettingsError * peError);
void (OPENVR_FNTABLE_CALLTYPE *RemoveSection)(char * pchSection, EVRSettingsError * peError);
void (OPENVR_FNTABLE_CALLTYPE *RemoveKeyInSection)(char * pchSection, char * pchSettingsKey, EVRSettingsError * peError);
};
@@ -1609,6 +1709,12 @@ struct VR_IVRScreenshots_FnTable
EVRScreenshotError (OPENVR_FNTABLE_CALLTYPE *SubmitScreenshot)(ScreenshotHandle_t screenshotHandle, EVRScreenshotType type, char * pchSourcePreviewFilename, char * pchSourceVRFilename);
};
struct VR_IVRResources_FnTable
{
uint32_t (OPENVR_FNTABLE_CALLTYPE *LoadSharedResource)(char * pchResourceName, char * pchBuffer, uint32_t unBufferLen);
uint32_t (OPENVR_FNTABLE_CALLTYPE *GetResourceFullPath)(char * pchResourceName, char * pchResourceTypeDirectory, char * pchPathBuffer, uint32_t unBufferLen);
};
#if 0
// Global entry points

View File

@@ -13,7 +13,13 @@
// vrtypes.h
#ifndef _INCLUDE_VRTYPES_H
#define _INCLUDE_VRTYPES_H
#define _INCLUDE_VRTYPES_H
// Forward declarations to avoid requiring vulkan.h
struct VkDevice_T;
struct VkPhysicalDevice_T;
struct VkInstance_T;
struct VkQueue_T;
namespace vr
{
@@ -125,6 +131,10 @@ struct Texture_t
EColorSpace eColorSpace;
};
// Handle to a shared texture (HANDLE on Windows obtained using OpenSharedResource).
typedef uint64_t SharedTextureHandle_t;
#define INVALID_SHARED_TEXTURE_HANDLE ((vr::SharedTextureHandle_t)0)
enum ETrackingResult
{
TrackingResult_Uninitialized = 1,
@@ -154,6 +164,8 @@ enum ETrackedDeviceClass
TrackedDeviceClass_Controller = 2, // Tracked controllers
TrackedDeviceClass_TrackingReference = 4, // Camera and base stations that serve as tracking reference points
TrackedDeviceClass_Count, // This isn't a class that will ever be returned. It is used for allocating arrays and such
TrackedDeviceClass_Other = 1000,
};
@@ -277,6 +289,7 @@ enum ETrackedDeviceProperty
Prop_Axis2Type_Int32 = 3004, // Return value is of type EVRControllerAxisType
Prop_Axis3Type_Int32 = 3005, // Return value is of type EVRControllerAxisType
Prop_Axis4Type_Int32 = 3006, // Return value is of type EVRControllerAxisType
Prop_ControllerRoleHint_Int32 = 3007, // Return value is of type ETrackedControllerRole
// Properties that are unique to TrackedDeviceClass_TrackingReference
Prop_FieldOfViewLeftDegrees_Float = 4000,
@@ -287,6 +300,17 @@ enum ETrackedDeviceProperty
Prop_TrackingRangeMaximumMeters_Float = 4005,
Prop_ModeLabel_String = 4006,
// Properties that are used for user interface like icons names
Prop_IconPathName_String = 5000, // usually a directory named "icons"
Prop_NamedIconPathDeviceOff_String = 5001, // PNG for static icon, or GIF for animation, 50x32 for headsets and 32x32 for others
Prop_NamedIconPathDeviceSearching_String = 5002, // PNG for static icon, or GIF for animation, 50x32 for headsets and 32x32 for others
Prop_NamedIconPathDeviceSearchingAlert_String = 5003, // PNG for static icon, or GIF for animation, 50x32 for headsets and 32x32 for others
Prop_NamedIconPathDeviceReady_String = 5004, // PNG for static icon, or GIF for animation, 50x32 for headsets and 32x32 for others
Prop_NamedIconPathDeviceReadyAlert_String = 5005, // PNG for static icon, or GIF for animation, 50x32 for headsets and 32x32 for others
Prop_NamedIconPathDeviceNotReady_String = 5006, // PNG for static icon, or GIF for animation, 50x32 for headsets and 32x32 for others
Prop_NamedIconPathDeviceStandby_String = 5007, // PNG for static icon, or GIF for animation, 50x32 for headsets and 32x32 for others
Prop_NamedIconPathDeviceAlertLow_String = 5008, // PNG for static icon, or GIF for animation, 50x32 for headsets and 32x32 for others
// Vendors are free to expose private debug data in this reserved region
Prop_VendorSpecific_Reserved_Start = 10000,
Prop_VendorSpecific_Reserved_End = 10999,
@@ -332,6 +356,22 @@ enum EVRSubmitFlags
// If the texture pointer passed in is actually a renderbuffer (e.g. for MSAA in OpenGL) then set this flag.
Submit_GlRenderBuffer = 0x02,
// Handle is pointer to VulkanData_t
Submit_VulkanTexture = 0x04,
};
/** Data required for passing Vulkan textures to IVRCompositor::Submit.
* Be sure to call OpenVR_Shutdown before destroying these resources. */
struct VulkanData_t
{
uint64_t m_nImage; // VkImage
VkDevice_T *m_pDevice;
VkPhysicalDevice_T *m_pPhysicalDevice;
VkInstance_T *m_pInstance;
VkQueue_T *m_pQueue;
uint32_t m_nQueueFamilyIndex;
uint32_t m_nWidth, m_nHeight, m_nFormat, m_nSampleCount;
};
@@ -346,6 +386,7 @@ enum EVRState
VRState_Ready_Alert = 4,
VRState_NotReady = 5,
VRState_Standby = 6,
VRState_Ready_Alert_Low = 7,
};
/** The types of events that could be posted (and what the parameters mean for each event type) */
@@ -362,6 +403,8 @@ enum EVREventType
VREvent_EnterStandbyMode = 106,
VREvent_LeaveStandbyMode = 107,
VREvent_TrackedDeviceRoleChanged = 108,
VREvent_WatchdogWakeUpRequested = 109,
VREvent_LensDistortionChanged = 110,
VREvent_ButtonPress = 200, // data is controller
VREvent_ButtonUnpress = 201, // data is controller
@@ -375,6 +418,7 @@ enum EVREventType
VREvent_FocusLeave = 304, // data is overlay
VREvent_Scroll = 305, // data is mouse
VREvent_TouchPadMove = 306, // data is mouse
VREvent_OverlayFocusChanged = 307, // data is overlay, global event
VREvent_InputFocusCaptured = 400, // data is process DEPRECATED
VREvent_InputFocusReleased = 401, // data is process DEPRECATED
@@ -406,12 +450,14 @@ enum EVREventType
VREvent_DashboardGuideButtonUp = 515,
VREvent_ScreenshotTriggered = 516, // Screenshot button combo was pressed, Dashboard should request a screenshot
VREvent_ImageFailed = 517, // Sent to overlays when a SetOverlayRaw or SetOverlayfromFail fails to load
VREvent_DashboardOverlayCreated = 518,
// Screenshot API
VREvent_RequestScreenshot = 520, // Sent by vrclient application to compositor to take a screenshot
VREvent_ScreenshotTaken = 521, // Sent by compositor to the application that the screenshot has been taken
VREvent_ScreenshotFailed = 522, // Sent by compositor to the application that the screenshot failed to be taken
VREvent_SubmitScreenshotToDashboard = 523, // Sent by compositor to the dashboard that a completed screenshot was submitted
VREvent_ScreenshotProgressToDashboard = 524, // Sent by compositor to the dashboard that a completed screenshot was submitted
VREvent_Notification_Shown = 600,
VREvent_Notification_Hidden = 601,
@@ -437,6 +483,7 @@ enum EVREventType
VREvent_ReprojectionSettingHasChanged = 852,
VREvent_ModelSkinSettingsHaveChanged = 853,
VREvent_EnvironmentSettingsHaveChanged = 854,
VREvent_PowerSettingsHaveChanged = 855,
VREvent_StatusUpdate = 900,
@@ -453,6 +500,7 @@ enum EVREventType
VREvent_ApplicationTransitionAborted = 1301,
VREvent_ApplicationTransitionNewAppStarted = 1302,
VREvent_ApplicationListUpdated = 1303,
VREvent_ApplicationMimeTypeLoad = 1304,
VREvent_Compositor_MirrorWindowShown = 1400,
VREvent_Compositor_MirrorWindowHidden = 1401,
@@ -463,6 +511,7 @@ enum EVREventType
VREvent_TrackedCamera_StopVideoStream = 1501,
VREvent_TrackedCamera_PauseVideoStream = 1502,
VREvent_TrackedCamera_ResumeVideoStream = 1503,
VREvent_TrackedCamera_EditingSurface = 1550,
VREvent_PerformanceTest_EnableCapture = 1600,
VREvent_PerformanceTest_DisableCapture = 1601,
@@ -496,6 +545,8 @@ enum EVRButtonId
k_EButton_DPad_Right = 5,
k_EButton_DPad_Down = 6,
k_EButton_A = 7,
k_EButton_ProximitySensor = 31,
k_EButton_Axis0 = 32,
k_EButton_Axis1 = 33,
@@ -634,6 +685,23 @@ struct VREvent_Screenshot_t
uint32_t type;
};
struct VREvent_ScreenshotProgress_t
{
float progress;
};
struct VREvent_ApplicationLaunch_t
{
uint32_t pid;
uint32_t unArgsHandle;
};
struct VREvent_EditingCameraSurface_t
{
uint64_t overlayHandle;
uint32_t nVisualMode;
};
/** If you change this you must manually update openvr_interop.cs.py */
typedef union
{
@@ -652,6 +720,9 @@ typedef union
VREvent_TouchPadMove_t touchPadMove;
VREvent_SeatedZeroPoseReset_t seatedZeroPoseReset;
VREvent_Screenshot_t screenshot;
VREvent_ScreenshotProgress_t screenshotProgress;
VREvent_ApplicationLaunch_t applicationLaunch;
VREvent_EditingCameraSurface_t cameraSurface;
} VREvent_Data_t;
/** An event posted by the server to all running applications */
@@ -779,7 +850,7 @@ enum EVROverlayError
VROverlayError_RequestFailed = 23,
VROverlayError_InvalidTexture = 24,
VROverlayError_UnableToLoadFile = 25,
VROVerlayError_KeyboardAlreadyInUse = 26,
VROverlayError_KeyboardAlreadyInUse = 26,
VROverlayError_NoNeighbor = 27,
};
@@ -795,6 +866,9 @@ enum EVRApplicationType
VRApplication_Utility = 4, // Init should not try to load any drivers. The application needs access to utility
// interfaces (like IVRSettings and IVRApplications) but not hardware.
VRApplication_VRMonitor = 5, // Reserved for vrmonitor
VRApplication_SteamWatchdog = 6,// Reserved for Steam
VRApplication_Max
};
@@ -851,6 +925,14 @@ enum EVRInitError
VRInitError_Init_NotSupportedWithCompositor = 122,
VRInitError_Init_NotAvailableToUtilityApps = 123,
VRInitError_Init_Internal = 124,
VRInitError_Init_HmdDriverIdIsNone = 125,
VRInitError_Init_HmdNotFoundPresenceFailed = 126,
VRInitError_Init_VRMonitorNotFound = 127,
VRInitError_Init_VRMonitorStartupFailed = 128,
VRInitError_Init_LowPowerWatchdogNotSupported = 129,
VRInitError_Init_InvalidApplicationType = 130,
VRInitError_Init_NotAvailableToWatchdogApps = 131,
VRInitError_Init_WatchdogDisabledInSettings = 132,
VRInitError_Driver_Failed = 200,
VRInitError_Driver_Unknown = 201,
@@ -861,13 +943,20 @@ enum EVRInitError
VRInitError_Driver_NotCalibrated = 206,
VRInitError_Driver_CalibrationInvalid = 207,
VRInitError_Driver_HmdDisplayNotFound = 208,
VRInitError_Driver_TrackedDeviceInterfaceUnknown = 209,
// VRInitError_Driver_HmdDisplayNotFoundAfterFix = 210, // not needed: here for historic reasons
VRInitError_Driver_HmdDriverIdOutOfBounds = 211,
VRInitError_Driver_HmdDisplayMirrored = 212,
VRInitError_IPC_ServerInitFailed = 300,
VRInitError_IPC_ConnectFailed = 301,
VRInitError_IPC_SharedStateInitFailed = 302,
VRInitError_IPC_CompositorInitFailed = 303,
VRInitError_IPC_MutexInitFailed = 304,
VRInitError_IPC_Failed = 305,
VRInitError_IPC_CompositorConnectFailed = 306,
VRInitError_IPC_CompositorInvalidConnectResponse = 307,
VRInitError_IPC_ConnectFailedAfterMultipleAttempts = 308,
VRInitError_Compositor_Failed = 400,
VRInitError_Compositor_D3D11HardwareRequired = 401,
@@ -971,7 +1060,7 @@ static const uint32_t k_unScreenshotHandleInvalid = 0;
#define VR_INTERFACE extern "C" __declspec( dllimport )
#endif
#elif defined(GNUC) || defined(COMPILER_GCC) || defined(__APPLE__)
#elif defined(__GNUC__) || defined(COMPILER_GCC) || defined(__APPLE__)
#ifdef VR_API_EXPORT
#define VR_INTERFACE extern "C" __attribute__((visibility("default")))
@@ -995,6 +1084,25 @@ static const uint32_t k_unScreenshotHandleInvalid = 0;
#endif // _INCLUDE_VRTYPES_H
// vrannotation.h
#ifdef API_GEN
# define VR_CLANG_ATTR(ATTR) __attribute__((annotate( ATTR )))
#else
# define VR_CLANG_ATTR(ATTR)
#endif
#define VR_METHOD_DESC(DESC) VR_CLANG_ATTR( "desc:" #DESC ";" )
#define VR_IGNOREATTR() VR_CLANG_ATTR( "ignore" )
#define VR_OUT_STRUCT() VR_CLANG_ATTR( "out_struct: ;" )
#define VR_OUT_STRING() VR_CLANG_ATTR( "out_string: ;" )
#define VR_OUT_ARRAY_CALL(COUNTER,FUNCTION,PARAMS) VR_CLANG_ATTR( "out_array_call:" #COUNTER "," #FUNCTION "," #PARAMS ";" )
#define VR_OUT_ARRAY_COUNT(COUNTER) VR_CLANG_ATTR( "out_array_count:" #COUNTER ";" )
#define VR_ARRAY_COUNT(COUNTER) VR_CLANG_ATTR( "array_count:" #COUNTER ";" )
#define VR_ARRAY_COUNT_D(COUNTER, DESC) VR_CLANG_ATTR( "array_count:" #COUNTER ";desc:" #DESC )
#define VR_BUFFER_COUNT(COUNTER) VR_CLANG_ATTR( "buffer_count:" #COUNTER ";" )
#define VR_OUT_BUFFER_COUNT(COUNTER) VR_CLANG_ATTR( "out_buffer_count:" #COUNTER ";" )
#define VR_OUT_STRING_COUNT(COUNTER) VR_CLANG_ATTR( "out_string_count:" #COUNTER ";" )
// vrtrackedcameratypes.h
#ifndef _VRTRACKEDCAMERATYPES_H
#define _VRTRACKEDCAMERATYPES_H
@@ -1102,6 +1210,8 @@ namespace vr
VRSettingsError_IPCFailed = 1,
VRSettingsError_WriteFailed = 2,
VRSettingsError_ReadFailed = 3,
VRSettingsError_JsonParseFailed = 4,
VRSettingsError_UnsetSettingHasNoDefault = 5, // This will be returned if the setting does not appear in the appropriate default file and has not been set
};
// The maximum length of a settings key
@@ -1115,21 +1225,24 @@ namespace vr
// Returns true if file sync occurred (force or settings dirty)
virtual bool Sync( bool bForce = false, EVRSettingsError *peError = nullptr ) = 0;
virtual bool GetBool( const char *pchSection, const char *pchSettingsKey, bool bDefaultValue, EVRSettingsError *peError = nullptr ) = 0;
virtual void SetBool( const char *pchSection, const char *pchSettingsKey, bool bValue, EVRSettingsError *peError = nullptr ) = 0;
virtual int32_t GetInt32( const char *pchSection, const char *pchSettingsKey, int32_t nDefaultValue, EVRSettingsError *peError = nullptr ) = 0;
virtual void SetInt32( const char *pchSection, const char *pchSettingsKey, int32_t nValue, EVRSettingsError *peError = nullptr ) = 0;
virtual float GetFloat( const char *pchSection, const char *pchSettingsKey, float flDefaultValue, EVRSettingsError *peError = nullptr ) = 0;
virtual void SetFloat( const char *pchSection, const char *pchSettingsKey, float flValue, EVRSettingsError *peError = nullptr ) = 0;
virtual void GetString( const char *pchSection, const char *pchSettingsKey, char *pchValue, uint32_t unValueLen, const char *pchDefaultValue, EVRSettingsError *peError = nullptr ) = 0;
virtual void SetString( const char *pchSection, const char *pchSettingsKey, const char *pchValue, EVRSettingsError *peError = nullptr ) = 0;
// Users of the system need to provide a proper default in default.vrsettings in the resources/settings/ directory
// of either the runtime or the driver_xxx directory. Otherwise the default will be false, 0, 0.0 or ""
virtual bool GetBool( const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr ) = 0;
virtual int32_t GetInt32( const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr ) = 0;
virtual float GetFloat( const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr ) = 0;
virtual void GetString( const char *pchSection, const char *pchSettingsKey, VR_OUT_STRING() char *pchValue, uint32_t unValueLen, EVRSettingsError *peError = nullptr ) = 0;
virtual void RemoveSection( const char *pchSection, EVRSettingsError *peError = nullptr ) = 0;
virtual void RemoveKeyInSection( const char *pchSection, const char *pchSettingsKey, EVRSettingsError *peError = nullptr ) = 0;
};
//-----------------------------------------------------------------------------
static const char * const IVRSettings_Version = "IVRSettings_001";
static const char * const IVRSettings_Version = "IVRSettings_002";
//-----------------------------------------------------------------------------
// steamvr keys
@@ -1154,9 +1267,6 @@ namespace vr
static const char * const k_pch_SteamVR_PlayAreaColor_String = "playAreaColor";
static const char * const k_pch_SteamVR_ShowStage_Bool = "showStage";
static const char * const k_pch_SteamVR_ActivateMultipleDrivers_Bool = "activateMultipleDrivers";
static const char * const k_pch_SteamVR_PowerOffOnExit_Bool = "powerOffOnExit";
static const char * const k_pch_SteamVR_StandbyAppRunningTimeout_Float = "standbyAppRunningTimeout";
static const char * const k_pch_SteamVR_StandbyNoAppTimeout_Float = "standbyNoAppTimeout";
static const char * const k_pch_SteamVR_DirectMode_Bool = "directMode";
static const char * const k_pch_SteamVR_DirectModeEdidVid_Int32 = "directModeEdidVid";
static const char * const k_pch_SteamVR_DirectModeEdidPid_Int32 = "directModeEdidPid";
@@ -1170,6 +1280,13 @@ namespace vr
static const char * const k_pch_SteamVR_ForceFadeOnBadTracking_Bool = "forceFadeOnBadTracking";
static const char * const k_pch_SteamVR_DefaultMirrorView_Int32 = "defaultMirrorView";
static const char * const k_pch_SteamVR_ShowMirrorView_Bool = "showMirrorView";
static const char * const k_pch_SteamVR_MirrorViewGeometry_String = "mirrorViewGeometry";
static const char * const k_pch_SteamVR_StartMonitorFromAppLaunch = "startMonitorFromAppLaunch";
static const char * const k_pch_SteamVR_EnableHomeApp = "enableHomeApp";
static const char * const k_pch_SteamVR_SetInitialDefaultHomeApp = "setInitialDefaultHomeApp";
static const char * const k_pch_SteamVR_CycleBackgroundImageTimeSec_Int32 = "CycleBackgroundImageTimeSec";
static const char * const k_pch_SteamVR_RetailDemo_Bool = "retailDemo";
//-----------------------------------------------------------------------------
// lighthouse keys
@@ -1180,9 +1297,6 @@ namespace vr
static const char * const k_pch_Lighthouse_DisambiguationDebug_Int32 = "disambiguationdebug";
static const char * const k_pch_Lighthouse_PrimaryBasestation_Int32 = "primarybasestation";
static const char * const k_pch_Lighthouse_LighthouseName_String = "lighthousename";
static const char * const k_pch_Lighthouse_MaxIncidenceAngleDegrees_Float = "maxincidenceangledegrees";
static const char * const k_pch_Lighthouse_UseLighthouseDirect_Bool = "uselighthousedirect";
static const char * const k_pch_Lighthouse_DBHistory_Bool = "dbhistory";
//-----------------------------------------------------------------------------
@@ -1205,7 +1319,8 @@ namespace vr
// user interface keys
static const char * const k_pch_UserInterface_Section = "userinterface";
static const char * const k_pch_UserInterface_StatusAlwaysOnTop_Bool = "StatusAlwaysOnTop";
static const char * const k_pch_UserInterface_EnableScreenshots_Bool = "EnableScreenshots";
static const char * const k_pch_UserInterface_Screenshots_Bool = "screenshots";
static const char * const k_pch_UserInterface_ScreenshotType_Int = "screenshotType";
//-----------------------------------------------------------------------------
// notification keys
@@ -1257,6 +1372,7 @@ namespace vr
static const char * const k_pch_Camera_BoundsColorGammaG_Int32 = "cameraBoundsColorGammaG";
static const char * const k_pch_Camera_BoundsColorGammaB_Int32 = "cameraBoundsColorGammaB";
static const char * const k_pch_Camera_BoundsColorGammaA_Int32 = "cameraBoundsColorGammaA";
static const char * const k_pch_Camera_BoundsStrength_Int32 = "cameraBoundsStrength";
//-----------------------------------------------------------------------------
// audio keys
@@ -1268,6 +1384,21 @@ namespace vr
static const char * const k_pch_audio_OffRecordDevice_String = "offRecordDevice";
static const char * const k_pch_audio_VIVEHDMIGain = "viveHDMIGain";
//-----------------------------------------------------------------------------
// power management keys
static const char * const k_pch_Power_Section = "power";
static const char * const k_pch_Power_PowerOffOnExit_Bool = "powerOffOnExit";
static const char * const k_pch_Power_TurnOffScreensTimeout_Float = "turnOffScreensTimeout";
static const char * const k_pch_Power_TurnOffControllersTimeout_Float = "turnOffControllersTimeout";
static const char * const k_pch_Power_ReturnToWatchdogTimeout_Float = "returnToWatchdogTimeout";
static const char * const k_pch_Power_AutoLaunchSteamVROnButtonPress = "autoLaunchSteamVROnButtonPress";
//-----------------------------------------------------------------------------
// dashboard keys
static const char * const k_pch_Dashboard_Section = "dashboard";
static const char * const k_pch_Dashboard_EnableDashboard_Bool = "enableDashboard";
static const char * const k_pch_Dashboard_ArcadeMode_Bool = "arcadeMode";
//-----------------------------------------------------------------------------
// model skin keys
static const char * const k_pch_modelskin_Section = "modelskins";
@@ -1373,8 +1504,8 @@ public:
* and thread use it can when it is deactivated */
virtual void Deactivate() = 0;
/** Handles a request from the system to power off this device */
virtual void PowerOff() = 0;
/** Handles a request from the system to put this device into standby mode. What that means is defined per-device. */
virtual void EnterStandby() = 0;
/** Requests a component interface of the driver for device-specific functionality. The driver should return NULL
* if the requested interface or version is not supported. */
@@ -1487,27 +1618,27 @@ namespace vr
// -----------------------------------
/** Specific to Oculus compositor support, textures supplied must be created using this method. */
virtual void CreateSwapTextureSet( uint32_t unPid, uint32_t unFormat, uint32_t unWidth, uint32_t unHeight, void *(*pSharedTextureHandles)[3] ) {}
virtual void CreateSwapTextureSet( uint32_t unPid, uint32_t unFormat, uint32_t unWidth, uint32_t unHeight, vr::SharedTextureHandle_t( *pSharedTextureHandles )[ 3 ] ) {}
/** Used to textures created using CreateSwapTextureSet. Only one of the set's handles needs to be used to destroy the entire set. */
virtual void DestroySwapTextureSet( void *pSharedTextureHandle ) {}
virtual void DestroySwapTextureSet( vr::SharedTextureHandle_t sharedTextureHandle ) {}
/** Used to purge all texture sets for a given process. */
virtual void DestroyAllSwapTextureSets( uint32_t unPid ) {}
/** After Present returns, calls this to get the next index to use for rendering. */
virtual void GetNextSwapTextureSetIndex( void *pSharedTextureHandles[ 2 ], uint32_t( *pIndices )[ 2 ] ) {}
virtual void GetNextSwapTextureSetIndex( vr::SharedTextureHandle_t sharedTextureHandles[ 2 ], uint32_t( *pIndices )[ 2 ] ) {}
/** Call once per layer to draw for this frame. One shared texture handle per eye. Textures must be created
* using CreateSwapTextureSet and should be alternated per frame. Call Present once all layers have been submitted. */
virtual void SubmitLayer( void *pSharedTextureHandles[ 2 ], const vr::VRTextureBounds_t( &bounds )[ 2 ], const vr::HmdMatrix34_t *pPose ) {}
virtual void SubmitLayer( vr::SharedTextureHandle_t sharedTextureHandles[ 2 ], const vr::VRTextureBounds_t( &bounds )[ 2 ], const vr::HmdMatrix34_t *pPose ) {}
/** Submits queued layers for display. */
virtual void Present( void *hSyncTexture ) {}
virtual void Present( vr::SharedTextureHandle_t syncTexture ) {}
};
static const char *IVRDriverDirectModeComponent_Version = "IVRDriverDirectModeComponent_001";
static const char *IVRDriverDirectModeComponent_Version = "IVRDriverDirectModeComponent_002";
}
@@ -1543,7 +1674,6 @@ namespace vr
// ivrcameracomponent.h
namespace vr
{
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
class ICameraVideoSinkCallback
@@ -1561,8 +1691,6 @@ namespace vr
// ------------------------------------
// Camera Methods
// ------------------------------------
virtual bool HasCamera() = 0;
virtual bool GetCameraFirmwareDescription( char *pBuffer, uint32_t nBufferLen ) = 0;
virtual bool GetCameraFrameDimensions( vr::ECameraVideoStreamFormat nVideoStreamFormat, uint32_t *pWidth, uint32_t *pHeight ) = 0;
virtual bool GetCameraFrameBufferingRequirements( int *pDefaultFrameQueueSize, uint32_t *pFrameBufferDataSize ) = 0;
virtual bool SetCameraFrameBuffering( int nFrameBufferCount, void **ppFrameBuffers, uint32_t nFrameBufferDataSize ) = 0;
@@ -1570,19 +1698,14 @@ namespace vr
virtual vr::ECameraVideoStreamFormat GetCameraVideoStreamFormat() = 0;
virtual bool StartVideoStream() = 0;
virtual void StopVideoStream() = 0;
virtual bool IsVideoStreamActive() = 0;
virtual float GetVideoStreamElapsedTime() = 0;
virtual bool IsVideoStreamActive( bool *pbPaused, float *pflElapsedTime ) = 0;
virtual const vr::CameraVideoStreamFrame_t *GetVideoStreamFrame() = 0;
virtual void ReleaseVideoStreamFrame( const vr::CameraVideoStreamFrame_t *pFrameImage ) = 0;
virtual bool SetAutoExposure( bool bEnable ) = 0;
virtual bool PauseVideoStream() = 0;
virtual bool ResumeVideoStream() = 0;
virtual bool IsVideoStreamPaused() = 0;
virtual bool GetCameraDistortion( float flInputU, float flInputV, float *pflOutputU, float *pflOutputV ) = 0;
virtual bool GetCameraProjection( float flWidthPixels, float flHeightPixels, float flZNear, float flZFar, vr::HmdMatrix44_t *pProjection ) = 0;
virtual bool GetRecommendedCameraUndistortion( uint32_t *pUndistortionWidthPixels, uint32_t *pUndistortionHeightPixels ) = 0;
virtual bool SetCameraUndistortion( uint32_t nUndistortionWidthPixels, uint32_t nUndistortionHeightPixels ) = 0;
virtual bool GetCameraFirmwareVersion( uint64_t *pFirmwareVersion ) = 0;
virtual bool GetCameraProjection( vr::EVRTrackedCameraFrameType eFrameType, float flZNear, float flZFar, vr::HmdMatrix44_t *pProjection ) = 0;
virtual bool SetFrameRate( int nISPFrameRate, int nSensorFrameRate ) = 0;
virtual bool SetCameraVideoSinkCallback( vr::ICameraVideoSinkCallback *pCameraVideoSinkCallback ) = 0;
virtual bool GetCameraCompatibilityMode( vr::ECameraCompatibilityMode *pCameraCompatibilityMode ) = 0;
@@ -1591,7 +1714,7 @@ namespace vr
virtual bool GetCameraIntrinsics( vr::EVRTrackedCameraFrameType eFrameType, HmdVector2_t *pFocalLength, HmdVector2_t *pCenter ) = 0;
};
static const char *IVRCameraComponent_Version = "IVRCameraComponent_001";
static const char *IVRCameraComponent_Version = "IVRCameraComponent_002";
}
// itrackeddevicedriverprovider.h
namespace vr
@@ -1754,9 +1877,20 @@ public:
/** always returns a pointer to a valid interface pointer of IVRSettings */
virtual IVRSettings *GetSettings( const char *pchInterfaceVersion ) = 0;
/** Client drivers in watchdog mode should call this when they have received a signal from hardware that should
* cause SteamVR to start */
virtual void WatchdogWakeUp() = 0;
};
/** Defines the mode that the client driver should start in. */
enum EClientDriverMode
{
ClientDriverMode_Normal = 0,
ClientDriverMode_Watchdog = 1, // client should return VRInitError_Init_LowPowerWatchdogNotSupported if it can't support this mode
};
/** This interface must be implemented in each driver. It will be loaded in vrclient.dll */
class IClientTrackedDeviceProvider
@@ -1772,7 +1906,7 @@ public:
* config files.
* pchDriverInstallDir - The absolute path of the root directory for the driver.
*/
virtual EVRInitError Init( IDriverLog *pDriverLog, vr::IClientDriverHost *pDriverHost, const char *pchUserDriverConfigDir, const char *pchDriverInstallDir ) = 0;
virtual EVRInitError Init( EClientDriverMode eDriverMode, IDriverLog *pDriverLog, vr::IClientDriverHost *pDriverHost, const char *pchUserDriverConfigDir, const char *pchDriverInstallDir ) = 0;
/** cleans up the driver right before it is unloaded */
virtual void Cleanup() = 0;
@@ -1800,7 +1934,7 @@ public:
virtual uint32_t GetMCImage( uint32_t *pImgWidth, uint32_t *pImgHeight, uint32_t *pChannels, void *pDataBuffer, uint32_t unBufferLen ) = 0;
};
static const char *IClientTrackedDeviceProvider_Version = "IClientTrackedDeviceProvider_003";
static const char *IClientTrackedDeviceProvider_Version = "IClientTrackedDeviceProvider_004";
}

View File

@@ -1,42 +1,67 @@
import pybullet as p
import time
p.connect(p.GUI)
p.connect(p.SHARED_MEMORY)
p.loadURDF("plane.urdf")
p.loadURDF("quadruped/quadruped.urdf",0,0,0.2)
quadruped = p.loadURDF("quadruped/quadruped.urdf",0,0,.3)
#p.getNumJoints(1)
#right front leg
p.resetJointState(1,0,1.57)
p.resetJointState(1,2,-2.2)
p.resetJointState(1,3,-1.57)
p.resetJointState(1,5,2.2)
p.createConstraint(1,2,1,5,3,[0,0,0],[0,0.01,0.2],[0,-0.015,0.2])
p.resetJointState(quadruped,0,1.57)
p.resetJointState(quadruped,2,-2.2)
p.resetJointState(quadruped,3,-1.57)
p.resetJointState(quadruped,5,2.2)
p.createConstraint(quadruped,2,quadruped,5,3,[0,0,0],[0,0.01,0.2],[0,-0.015,0.2])
p.setJointMotorControl(quadruped,0,p.VELOCITY_CONTROL,1,10)
p.setJointMotorControl(quadruped,1,p.VELOCITY_CONTROL,0,0)
p.setJointMotorControl(quadruped,2,p.VELOCITY_CONTROL,0,0)
p.setJointMotorControl(quadruped,3,p.VELOCITY_CONTROL,-1,10)
p.setJointMotorControl(quadruped,4,p.VELOCITY_CONTROL,0,0)
p.setJointMotorControl(quadruped,5,p.VELOCITY_CONTROL,0,0)
#left front leg
p.resetJointState(1,6,1.57)
p.resetJointState(1,8,-2.2)
p.resetJointState(1,9,-1.57)
p.resetJointState(1,11,2.2)
p.createConstraint(1,8,1,11,3,[0,0,0],[0,-0.01,0.2],[0,0.015,0.2])
p.resetJointState(quadruped,6,1.57)
p.resetJointState(quadruped,8,-2.2)
p.resetJointState(quadruped,9,-1.57)
p.resetJointState(quadruped,11,2.2)
p.createConstraint(quadruped,8,quadruped,11,3,[0,0,0],[0,-0.01,0.2],[0,0.015,0.2])
p.setJointMotorControl(quadruped,6,p.VELOCITY_CONTROL,1,10)
p.setJointMotorControl(quadruped,7,p.VELOCITY_CONTROL,0,0)
p.setJointMotorControl(quadruped,8,p.VELOCITY_CONTROL,0,0)
p.setJointMotorControl(quadruped,9,p.VELOCITY_CONTROL,-1,10)
p.setJointMotorControl(quadruped,10,p.VELOCITY_CONTROL,0,0)
p.setJointMotorControl(quadruped,11,p.VELOCITY_CONTROL,0,0)
#right back leg
p.resetJointState(1,12,1.57)
p.resetJointState(1,14,-2.2)
p.resetJointState(1,15,-1.57)
p.resetJointState(1,17,2.2)
p.createConstraint(1,14,1,17,3,[0,0,0],[0,0.01,0.2],[0,-0.015,0.2])
p.resetJointState(quadruped,12,1.57)
p.resetJointState(quadruped,14,-2.2)
p.resetJointState(quadruped,15,-1.57)
p.resetJointState(quadruped,17,2.2)
p.createConstraint(quadruped,14,quadruped,17,3,[0,0,0],[0,0.01,0.2],[0,-0.015,0.2])
p.setJointMotorControl(quadruped,12,p.VELOCITY_CONTROL,6,10)
p.setJointMotorControl(quadruped,13,p.VELOCITY_CONTROL,0,0)
p.setJointMotorControl(quadruped,14,p.VELOCITY_CONTROL,0,0)
p.setJointMotorControl(quadruped,15,p.VELOCITY_CONTROL,-6,10)
p.setJointMotorControl(quadruped,16,p.VELOCITY_CONTROL,0,0)
p.setJointMotorControl(quadruped,17,p.VELOCITY_CONTROL,0,0)
#left back leg
p.resetJointState(1,18,1.57)
p.resetJointState(1,20,-2.2)
p.resetJointState(1,21,-1.57)
p.resetJointState(1,23,2.2)
p.createConstraint(1,20,1,23,3,[0,0,0],[0,-0.01,0.2],[0,0.015,0.2])
p.resetJointState(quadruped,18,1.57)
p.resetJointState(quadruped,20,-2.2)
p.resetJointState(quadruped,21,-1.57)
p.resetJointState(quadruped,23,2.2)
p.createConstraint(quadruped,20,quadruped,23,3,[0,0,0],[0,-0.01,0.2],[0,0.015,0.2])
p.setJointMotorControl(quadruped,18,p.VELOCITY_CONTROL,6,10)
p.setJointMotorControl(quadruped,19,p.VELOCITY_CONTROL,0,0)
p.setJointMotorControl(quadruped,20,p.VELOCITY_CONTROL,0,0)
p.setJointMotorControl(quadruped,21,p.VELOCITY_CONTROL,-6,10)
p.setJointMotorControl(quadruped,22,p.VELOCITY_CONTROL,0,0)
p.setJointMotorControl(quadruped,23,p.VELOCITY_CONTROL,0,0)
p.setGravity(0,0,-10)
t_end = time.time() + 120
i=0
while time.time() < t_end:
i = p.getNumJoints(0)
p.stepSimulation()