summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--build3/premake4.lua7
-rw-r--r--build_visual_studio_vr_pybullet_double.bat2
-rw-r--r--data/plane.obj14
-rw-r--r--data/plane.urdf4
-rw-r--r--examples/SharedMemory/PhysicsClientSharedMemory.cpp30
-rw-r--r--examples/SharedMemory/PhysicsServerCommandProcessor.cpp30
-rw-r--r--examples/SharedMemory/PhysicsServerExample.cpp392
-rw-r--r--examples/SharedMemory/PhysicsServerSharedMemory.h2
-rw-r--r--examples/SharedMemory/premake4.lua61
-rw-r--r--examples/StandaloneMain/hellovr_opengl_main.cpp18
-rw-r--r--examples/StandaloneMain/main_opengl_single_example.cpp3
-rw-r--r--examples/ThirdPartyLibs/midi/LICENSE.txt29
-rw-r--r--examples/ThirdPartyLibs/midi/RtError.h60
-rw-r--r--examples/ThirdPartyLibs/midi/RtMidi.cpp3803
-rw-r--r--examples/ThirdPartyLibs/midi/RtMidi.h675
-rw-r--r--examples/ThirdPartyLibs/midi/cmidiin.cpp112
-rw-r--r--examples/ThirdPartyLibs/midi/premake4.lua35
-rw-r--r--examples/ThirdPartyLibs/openvr/bin/linux32/libopenvr_api.sobin347110 -> 0 bytes
-rw-r--r--examples/ThirdPartyLibs/openvr/bin/linux64/libopenvr_api.sobin383669 -> 389560 bytes
-rw-r--r--examples/ThirdPartyLibs/openvr/bin/osx32/libopenvr_api.dylibbin299972 -> 304956 bytes
-rw-r--r--examples/ThirdPartyLibs/openvr/bin/win32/openvr_api.dllbin265024 -> 267040 bytes
-rw-r--r--examples/ThirdPartyLibs/openvr/bin/win64/openvr_api.dllbin311616 -> 314656 bytes
-rw-r--r--examples/ThirdPartyLibs/openvr/headers/openvr.h284
-rw-r--r--examples/ThirdPartyLibs/openvr/headers/openvr_api.cs411
-rw-r--r--examples/ThirdPartyLibs/openvr/headers/openvr_api.json363
-rw-r--r--examples/ThirdPartyLibs/openvr/headers/openvr_capi.h152
-rw-r--r--examples/ThirdPartyLibs/openvr/headers/openvr_driver.h210
-rw-r--r--examples/ThirdPartyLibs/openvr/lib/linux32/libopenvr_api.sobin2315918 -> 0 bytes
-rw-r--r--examples/ThirdPartyLibs/openvr/lib/linux64/libopenvr_api.sobin3129824 -> 3144159 bytes
-rw-r--r--examples/ThirdPartyLibs/openvr/lib/win32/openvr_api.libbin4864 -> 5750 bytes
-rw-r--r--examples/ThirdPartyLibs/openvr/lib/win64/openvr_api.libbin4806 -> 5668 bytes
-rw-r--r--examples/pybullet/quadruped.py79
32 files changed, 6406 insertions, 370 deletions
diff --git a/build3/premake4.lua b/build3/premake4.lua
index 06e85d591..525996461 100644
--- a/build3/premake4.lua
+++ b/build3/premake4.lua
@@ -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"
diff --git a/build_visual_studio_vr_pybullet_double.bat b/build_visual_studio_vr_pybullet_double.bat
index 6ca0652b9..f4c43cbb5 100644
--- a/build_visual_studio_vr_pybullet_double.bat
+++ b/build_visual_studio_vr_pybullet_double.bat
@@ -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
diff --git a/data/plane.obj b/data/plane.obj
index 0b77a9912..606209531 100644
--- a/data/plane.obj
+++ b/data/plane.obj
@@ -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
diff --git a/data/plane.urdf b/data/plane.urdf
index b2c2d7659..900080e08 100644
--- a/data/plane.urdf
+++ b/data/plane.urdf
@@ -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>
diff --git a/examples/SharedMemory/PhysicsClientSharedMemory.cpp b/examples/SharedMemory/PhysicsClientSharedMemory.cpp
index 9a323933a..e02d11e2d 100644
--- a/examples/SharedMemory/PhysicsClientSharedMemory.cpp
+++ b/examples/SharedMemory/PhysicsClientSharedMemory.cpp
@@ -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;
}
diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp
index 0a2cc253e..9791ab288 100644
--- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp
+++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp
@@ -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};
diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp
index 4e3ccf253..c4aa9455a 100644
--- a/examples/SharedMemory/PhysicsServerExample.cpp
+++ b/examples/SharedMemory/PhysicsServerExample.cpp
@@ -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,53 +1537,7 @@ 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();
}
}
diff --git a/examples/SharedMemory/PhysicsServerSharedMemory.h b/examples/SharedMemory/PhysicsServerSharedMemory.h
index f96e7ca4b..c330817b4 100644
--- a/examples/SharedMemory/PhysicsServerSharedMemory.h
+++ b/examples/SharedMemory/PhysicsServerSharedMemory.h
@@ -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);
diff --git a/examples/SharedMemory/premake4.lua b/examples/SharedMemory/premake4.lua
index 2bbf3b569..a17afb1f8 100644
--- a/examples/SharedMemory/premake4.lua
+++ b/examples/SharedMemory/premake4.lua
@@ -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",
diff --git a/examples/StandaloneMain/hellovr_opengl_main.cpp b/examples/StandaloneMain/hellovr_opengl_main.cpp
index 52b1574f3..d196c8ee8 100644
--- a/examples/StandaloneMain/hellovr_opengl_main.cpp
+++ b/examples/StandaloneMain/hellovr_opengl_main.cpp
@@ -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;
diff --git a/examples/StandaloneMain/main_opengl_single_example.cpp b/examples/StandaloneMain/main_opengl_single_example.cpp
index 8bf97619d..a040882c6 100644
--- a/examples/StandaloneMain/main_opengl_single_example.cpp
+++ b/examples/StandaloneMain/main_opengl_single_example.cpp
@@ -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();
diff --git a/examples/ThirdPartyLibs/midi/LICENSE.txt b/examples/ThirdPartyLibs/midi/LICENSE.txt
new file mode 100644
index 000000000..5b85f871c
--- /dev/null
+++ b/examples/ThirdPartyLibs/midi/LICENSE.txt
@@ -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.
+*/ \ No newline at end of file
diff --git a/examples/ThirdPartyLibs/midi/RtError.h b/examples/ThirdPartyLibs/midi/RtError.h
new file mode 100644
index 000000000..5cf7d510a
--- /dev/null
+++ b/examples/ThirdPartyLibs/midi/RtError.h
@@ -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 \ No newline at end of file
diff --git a/examples/ThirdPartyLibs/midi/RtMidi.cpp b/examples/ThirdPartyLibs/midi/RtMidi.cpp
new file mode 100644
index 000000000..9cbd260f0
--- /dev/null
+++ b/examples/ThirdPartyLibs/midi/RtMidi.cpp
@@ -0,0 +1,3803 @@
+/**********************************************************************/
+/*! \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.
+*/
+/**********************************************************************/
+
+// RtMidi: Version 2.0.1
+
+#include "RtMidi.h"
+#include <sstream>
+#include <stdlib.h> //exit
+
+//*********************************************************************//
+// RtMidi Definitions
+//*********************************************************************//
+
+void RtMidi :: getCompiledApi( std::vector<RtMidi::Api> &apis )
+{
+ apis.clear();
+
+ // The order here will control the order of RtMidi's API search in
+ // the constructor.
+#if defined(__MACOSX_CORE__)
+ apis.push_back( MACOSX_CORE );
+#endif
+#if defined(__LINUX_ALSA__)
+ apis.push_back( LINUX_ALSA );
+#endif
+#if defined(__UNIX_JACK__)
+ apis.push_back( UNIX_JACK );
+#endif
+#if defined(__WINDOWS_MM__)
+ apis.push_back( WINDOWS_MM );
+#endif
+#if defined(__WINDOWS_KS__)
+ apis.push_back( WINDOWS_KS );
+#endif
+#if defined(__RTMIDI_DUMMY__)
+ apis.push_back( RTMIDI_DUMMY );
+#endif
+
+}
+
+void RtMidi :: error( RtError::Type type, std::string errorString )
+{
+ if (type == RtError::WARNING) {
+ std::cerr << '\n' << errorString << "\n\n";
+ }
+ else if (type == RtError::DEBUG_WARNING) {
+#if defined(__RTMIDI_DEBUG__)
+ std::cerr << '\n' << errorString << "\n\n";
+#endif
+ }
+ else {
+ std::cerr << '\n' << errorString << "\n\n";
+// exit(0);
+ }
+}
+
+//*********************************************************************//
+// RtMidiIn Definitions
+//*********************************************************************//
+
+void RtMidiIn :: openMidiApi( RtMidi::Api api, const std::string clientName, unsigned int queueSizeLimit )
+{
+ if ( rtapi_ )
+ delete rtapi_;
+ rtapi_ = 0;
+
+#if defined(__UNIX_JACK__)
+ if ( api == UNIX_JACK )
+ rtapi_ = new MidiInJack( clientName, queueSizeLimit );
+#endif
+#if defined(__LINUX_ALSA__)
+ if ( api == LINUX_ALSA )
+ rtapi_ = new MidiInAlsa( clientName, queueSizeLimit );
+#endif
+#if defined(__WINDOWS_MM__)
+ if ( api == WINDOWS_MM )
+ rtapi_ = new MidiInWinMM( clientName, queueSizeLimit );
+#endif
+#if defined(__WINDOWS_KS__)
+ if ( api == WINDOWS_KS )
+ rtapi_ = new MidiInWinKS( clientName, queueSizeLimit );
+#endif
+#if defined(__MACOSX_CORE__)
+ if ( api == MACOSX_CORE )
+ rtapi_ = new MidiInCore( clientName, queueSizeLimit );
+#endif
+#if defined(__RTMIDI_DUMMY__)
+ if ( api == RTMIDI_DUMMY )
+ rtapi_ = new MidiInDummy( clientName, queueSizeLimit );
+#endif
+}
+
+RtMidiIn :: RtMidiIn( RtMidi::Api api, const std::string clientName, unsigned int queueSizeLimit )
+{
+ rtapi_ = 0;
+
+ if ( api != UNSPECIFIED ) {
+ // Attempt to open the specified API.
+ openMidiApi( api, clientName, queueSizeLimit );
+ if ( rtapi_ ) return;
+
+ // No compiled support for specified API value. Issue a debug
+ // warning and continue as if no API was specified.
+ RtMidi::error( RtError::WARNING, "RtMidiIn: no compiled support for specified API argument!" );
+ }
+
+ // Iterate through the compiled APIs and return as soon as we find
+ // one with at least one port or we reach the end of the list.
+ std::vector< RtMidi::Api > apis;
+ getCompiledApi( apis );
+ for ( unsigned int i=0; i<apis.size(); i++ ) {
+ openMidiApi( apis[i], clientName, queueSizeLimit );
+ if ( rtapi_->getPortCount() ) break;
+ }
+
+ if ( rtapi_ ) return;
+
+ // It should not be possible to get here because the preprocessor
+ // definition __RTMIDI_DUMMY__ is automatically defined if no
+ // API-specific definitions are passed to the compiler. But just in
+ // case something weird happens, we'll print out an error message.
+ RtMidi::error( RtError::WARNING, "RtMidiIn: no compiled API support found ... critical error!!" );
+}
+
+RtMidiIn :: ~RtMidiIn()
+{
+ delete rtapi_;
+}
+
+
+//*********************************************************************//
+// RtMidiOut Definitions
+//*********************************************************************//
+
+void RtMidiOut :: openMidiApi( RtMidi::Api api, const std::string clientName )
+{
+ if ( rtapi_ )
+ delete rtapi_;
+ rtapi_ = 0;
+
+#if defined(__UNIX_JACK__)
+ if ( api == UNIX_JACK )
+ rtapi_ = new MidiOutJack( clientName );
+#endif
+#if defined(__LINUX_ALSA__)
+ if ( api == LINUX_ALSA )
+ rtapi_ = new MidiOutAlsa( clientName );
+#endif
+#if defined(__WINDOWS_MM__)
+ if ( api == WINDOWS_MM )
+ rtapi_ = new MidiOutWinMM( clientName );
+#endif
+#if defined(__WINDOWS_KS__)
+ if ( api == WINDOWS_KS )
+ rtapi_ = new MidiOutWinKS( clientName );
+#endif
+#if defined(__MACOSX_CORE__)
+ if ( api == MACOSX_CORE )
+ rtapi_ = new MidiOutCore( clientName );
+#endif
+#if defined(__RTMIDI_DUMMY__)
+ if ( api == RTMIDI_DUMMY )
+ rtapi_ = new MidiOutDummy( clientName );
+#endif
+}
+
+RtMidiOut :: RtMidiOut( RtMidi::Api api, const std::string clientName )
+{
+ rtapi_ = 0;
+
+ if ( api != UNSPECIFIED ) {
+ // Attempt to open the specified API.
+ openMidiApi( api, clientName );
+ if ( rtapi_ ) return;
+
+ // No compiled support for specified API value. Issue a debug
+ // warning and continue as if no API was specified.
+ RtMidi::error( RtError::WARNING, "RtMidiOut: no compiled support for specified API argument!" );
+ }
+
+ // Iterate through the compiled APIs and return as soon as we find
+ // one with at least one port or we reach the end of the list.
+ std::vector< RtMidi::Api > apis;
+ getCompiledApi( apis );
+ for ( unsigned int i=0; i<apis.size(); i++ ) {
+ openMidiApi( apis[i], clientName );
+ if ( rtapi_->getPortCount() ) break;
+ }
+
+ if ( rtapi_ ) return;
+
+ // It should not be possible to get here because the preprocessor
+ // definition __RTMIDI_DUMMY__ is automatically defined if no
+ // API-specific definitions are passed to the compiler. But just in
+ // case something weird happens, we'll print out an error message.
+ RtMidi::error( RtError::WARNING, "RtMidiOut: no compiled API support found ... critical error!!" );
+}
+
+RtMidiOut :: ~RtMidiOut()
+{
+ delete rtapi_;
+}
+
+//*********************************************************************//
+// Common MidiInApi Definitions
+//*********************************************************************//
+
+MidiInApi :: MidiInApi( unsigned int queueSizeLimit )
+ : apiData_( 0 ), connected_( false )
+{
+ // Allocate the MIDI queue.
+ inputData_.queue.ringSize = queueSizeLimit;
+ if ( inputData_.queue.ringSize > 0 )
+ inputData_.queue.ring = new MidiMessage[ inputData_.queue.ringSize ];
+}
+
+MidiInApi :: ~MidiInApi( void )
+{
+ // Delete the MIDI queue.
+ if ( inputData_.queue.ringSize > 0 ) delete [] inputData_.queue.ring;
+}
+
+void MidiInApi :: setCallback( RtMidiIn::RtMidiCallback callback, void *userData )
+{
+ if ( inputData_.usingCallback ) {
+ errorString_ = "MidiInApi::setCallback: a callback function is already set!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return;
+ }
+
+ if ( !callback ) {
+ errorString_ = "RtMidiIn::setCallback: callback function value is invalid!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return;
+ }
+
+ inputData_.userCallback = (void *) callback;
+ inputData_.userData = userData;
+ inputData_.usingCallback = true;
+}
+
+void MidiInApi :: cancelCallback()
+{
+ if ( !inputData_.usingCallback ) {
+ errorString_ = "RtMidiIn::cancelCallback: no callback function was set!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return;
+ }
+
+ inputData_.userCallback = 0;
+ inputData_.userData = 0;
+ inputData_.usingCallback = false;
+}
+
+void MidiInApi :: ignoreTypes( bool midiSysex, bool midiTime, bool midiSense )
+{
+ inputData_.ignoreFlags = 0;
+ if ( midiSysex ) inputData_.ignoreFlags = 0x01;
+ if ( midiTime ) inputData_.ignoreFlags |= 0x02;
+ if ( midiSense ) inputData_.ignoreFlags |= 0x04;
+}
+
+double MidiInApi :: getMessage( std::vector<unsigned char> *message )
+{
+ message->clear();
+
+ if ( inputData_.usingCallback ) {
+ errorString_ = "RtMidiIn::getNextMessage: a user callback is currently set for this port.";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return 0.0;
+ }
+
+ if ( inputData_.queue.size == 0 ) return 0.0;
+
+ // Copy queued message to the vector pointer argument and then "pop" it.
+ std::vector<unsigned char> *bytes = &(inputData_.queue.ring[inputData_.queue.front].bytes);
+ message->assign( bytes->begin(), bytes->end() );
+ double deltaTime = inputData_.queue.ring[inputData_.queue.front].timeStamp;
+ inputData_.queue.size--;
+ inputData_.queue.front++;
+ if ( inputData_.queue.front == inputData_.queue.ringSize )
+ inputData_.queue.front = 0;
+
+ return deltaTime;
+}
+
+//*********************************************************************//
+// Common MidiOutApi Definitions
+//*********************************************************************//
+
+MidiOutApi :: MidiOutApi( void )
+ : apiData_( 0 ), connected_( false )
+{
+}
+
+MidiOutApi :: ~MidiOutApi( void )
+{
+}
+
+// *************************************************** //
+//
+// OS/API-specific methods.
+//
+// *************************************************** //
+
+#if defined(__MACOSX_CORE__)
+
+// The CoreMIDI API is based on the use of a callback function for
+// MIDI input. We convert the system specific time stamps to delta
+// time values.
+
+// OS-X CoreMIDI header files.
+#include <CoreMIDI/CoreMIDI.h>
+#include <CoreAudio/HostTime.h>
+#include <CoreServices/CoreServices.h>
+
+// A structure to hold variables related to the CoreMIDI API
+// implementation.
+struct CoreMidiData {
+ MIDIClientRef client;
+ MIDIPortRef port;
+ MIDIEndpointRef endpoint;
+ MIDIEndpointRef destinationId;
+ unsigned long long lastTime;
+ MIDISysexSendRequest sysexreq;
+};
+
+//*********************************************************************//
+// API: OS-X
+// Class Definitions: MidiInCore
+//*********************************************************************//
+
+void midiInputCallback( const MIDIPacketList *list, void *procRef, void *srcRef )
+{
+ MidiInApi::RtMidiInData *data = static_cast<MidiInApi::RtMidiInData *> (procRef);
+ CoreMidiData *apiData = static_cast<CoreMidiData *> (data->apiData);
+
+ unsigned char status;
+ unsigned short nBytes, iByte, size;
+ unsigned long long time;
+
+ bool& continueSysex = data->continueSysex;
+ MidiInApi::MidiMessage& message = data->message;
+
+ const MIDIPacket *packet = &list->packet[0];
+ for ( unsigned int i=0; i<list->numPackets; ++i ) {
+
+ // My interpretation of the CoreMIDI documentation: all message
+ // types, except sysex, are complete within a packet and there may
+ // be several of them in a single packet. Sysex messages can be
+ // broken across multiple packets and PacketLists but are bundled
+ // alone within each packet (these packets do not contain other
+ // message types). If sysex messages are split across multiple
+ // MIDIPacketLists, they must be handled by multiple calls to this
+ // function.
+
+ nBytes = packet->length;
+ if ( nBytes == 0 ) continue;
+
+ // Calculate time stamp.
+
+ if ( data->firstMessage ) {
+ message.timeStamp = 0.0;
+ data->firstMessage = false;
+ }
+ else {
+ time = packet->timeStamp;
+ if ( time == 0 ) { // this happens when receiving asynchronous sysex messages
+ time = AudioGetCurrentHostTime();
+ }
+ time -= apiData->lastTime;
+ time = AudioConvertHostTimeToNanos( time );
+ if ( !continueSysex )
+ message.timeStamp = time * 0.000000001;
+ }
+ apiData->lastTime = packet->timeStamp;
+ if ( apiData->lastTime == 0 ) { // this happens when receiving asynchronous sysex messages
+ apiData->lastTime = AudioGetCurrentHostTime();
+ }
+ //std::cout << "TimeStamp = " << packet->timeStamp << std::endl;
+
+ iByte = 0;
+ if ( continueSysex ) {
+ // We have a continuing, segmented sysex message.
+ if ( !( data->ignoreFlags & 0x01 ) ) {
+ // If we're not ignoring sysex messages, copy the entire packet.
+ for ( unsigned int j=0; j<nBytes; ++j )
+ message.bytes.push_back( packet->data[j] );
+ }
+ continueSysex = packet->data[nBytes-1] != 0xF7;
+
+ if ( !continueSysex ) {
+ // If not a continuing sysex message, invoke the user callback function or queue the message.
+ if ( data->usingCallback ) {
+ RtMidiIn::RtMidiCallback callback = (RtMidiIn::RtMidiCallback) data->userCallback;
+ callback( message.timeStamp, &message.bytes, data->userData );
+ }
+ else {
+ // As long as we haven't reached our queue size limit, push the message.
+ if ( data->queue.size < data->queue.ringSize ) {
+ data->queue.ring[data->queue.back++] = message;
+ if ( data->queue.back == data->queue.ringSize )
+ data->queue.back = 0;
+ data->queue.size++;
+ }
+ else
+ std::cerr << "\nMidiInCore: message queue limit reached!!\n\n";
+ }
+ message.bytes.clear();
+ }
+ }
+ else {
+ while ( iByte < nBytes ) {
+ size = 0;
+ // We are expecting that the next byte in the packet is a status byte.
+ status = packet->data[iByte];
+ if ( !(status & 0x80) ) break;
+ // Determine the number of bytes in the MIDI message.
+ if ( status < 0xC0 ) size = 3;
+ else if ( status < 0xE0 ) size = 2;
+ else if ( status < 0xF0 ) size = 3;
+ else if ( status == 0xF0 ) {
+ // A MIDI sysex
+ if ( data->ignoreFlags & 0x01 ) {
+ size = 0;
+ iByte = nBytes;
+ }
+ else size = nBytes - iByte;
+ continueSysex = packet->data[nBytes-1] != 0xF7;
+ }
+ else if ( status == 0xF1 ) {
+ // A MIDI time code message
+ if ( data->ignoreFlags & 0x02 ) {
+ size = 0;
+ iByte += 2;
+ }
+ else size = 2;
+ }
+ else if ( status == 0xF2 ) size = 3;
+ else if ( status == 0xF3 ) size = 2;
+ else if ( status == 0xF8 && ( data->ignoreFlags & 0x02 ) ) {
+ // A MIDI timing tick message and we're ignoring it.
+ size = 0;
+ iByte += 1;
+ }
+ else if ( status == 0xFE && ( data->ignoreFlags & 0x04 ) ) {
+ // A MIDI active sensing message and we're ignoring it.
+ size = 0;
+ iByte += 1;
+ }
+ else size = 1;
+
+ // Copy the MIDI data to our vector.
+ if ( size ) {
+ message.bytes.assign( &packet->data[iByte], &packet->data[iByte+size] );
+ if ( !continueSysex ) {
+ // If not a continuing sysex message, invoke the user callback function or queue the message.
+ if ( data->usingCallback ) {
+ RtMidiIn::RtMidiCallback callback = (RtMidiIn::RtMidiCallback) data->userCallback;
+ callback( message.timeStamp, &message.bytes, data->userData );
+ }
+ else {
+ // As long as we haven't reached our queue size limit, push the message.
+ if ( data->queue.size < data->queue.ringSize ) {
+ data->queue.ring[data->queue.back++] = message;
+ if ( data->queue.back == data->queue.ringSize )
+ data->queue.back = 0;
+ data->queue.size++;
+ }
+ else
+ std::cerr << "\nMidiInCore: message queue limit reached!!\n\n";
+ }
+ message.bytes.clear();
+ }
+ iByte += size;
+ }
+ }
+ }
+ packet = MIDIPacketNext(packet);
+ }
+}
+
+MidiInCore :: MidiInCore( const std::string clientName, unsigned int queueSizeLimit ) : MidiInApi( queueSizeLimit )
+{
+ initialize( clientName );
+}
+
+MidiInCore :: ~MidiInCore( void )
+{
+ // Close a connection if it exists.
+ closePort();
+
+ // Cleanup.
+ CoreMidiData *data = static_cast<CoreMidiData *> (apiData_);
+ MIDIClientDispose( data->client );
+ if ( data->endpoint ) MIDIEndpointDispose( data->endpoint );
+ delete data;
+}
+
+void MidiInCore :: initialize( const std::string& clientName )
+{
+ // Set up our client.
+ MIDIClientRef client;
+ OSStatus result = MIDIClientCreate( CFStringCreateWithCString( NULL, clientName.c_str(), kCFStringEncodingASCII ), NULL, NULL, &client );
+ if ( result != noErr ) {
+ errorString_ = "MidiInCore::initialize: error creating OS-X MIDI client object.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ // Save our api-specific connection information.
+ CoreMidiData *data = (CoreMidiData *) new CoreMidiData;
+ data->client = client;
+ data->endpoint = 0;
+ apiData_ = (void *) data;
+ inputData_.apiData = (void *) data;
+}
+
+void MidiInCore :: openPort( unsigned int portNumber, const std::string portName )
+{
+ if ( connected_ ) {
+ errorString_ = "MidiInCore::openPort: a valid connection already exists!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return;
+ }
+
+ unsigned int nSrc = MIDIGetNumberOfSources();
+ if (nSrc < 1) {
+ errorString_ = "MidiInCore::openPort: no MIDI input sources found!";
+ RtMidi::error( RtError::NO_DEVICES_FOUND, errorString_ );
+ }
+
+ std::ostringstream ost;
+ if ( portNumber >= nSrc ) {
+ ost << "MidiInCore::openPort: the 'portNumber' argument (" << portNumber << ") is invalid.";
+ errorString_ = ost.str();
+ RtMidi::error( RtError::INVALID_PARAMETER, errorString_ );
+ }
+
+ MIDIPortRef port;
+ CoreMidiData *data = static_cast<CoreMidiData *> (apiData_);
+ OSStatus result = MIDIInputPortCreate( data->client,
+ CFStringCreateWithCString( NULL, portName.c_str(), kCFStringEncodingASCII ),
+ midiInputCallback, (void *)&inputData_, &port );
+ if ( result != noErr ) {
+ MIDIClientDispose( data->client );
+ errorString_ = "MidiInCore::openPort: error creating OS-X MIDI input port.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ // Get the desired input source identifier.
+ MIDIEndpointRef endpoint = MIDIGetSource( portNumber );
+ if ( endpoint == 0 ) {
+ MIDIPortDispose( port );
+ MIDIClientDispose( data->client );
+ errorString_ = "MidiInCore::openPort: error getting MIDI input source reference.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ // Make the connection.
+ result = MIDIPortConnectSource( port, endpoint, NULL );
+ if ( result != noErr ) {
+ MIDIPortDispose( port );
+ MIDIClientDispose( data->client );
+ errorString_ = "MidiInCore::openPort: error connecting OS-X MIDI input port.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ // Save our api-specific port information.
+ data->port = port;
+
+ connected_ = true;
+}
+
+void MidiInCore :: openVirtualPort( const std::string portName )
+{
+ CoreMidiData *data = static_cast<CoreMidiData *> (apiData_);
+
+ // Create a virtual MIDI input destination.
+ MIDIEndpointRef endpoint;
+ OSStatus result = MIDIDestinationCreate( data->client,
+ CFStringCreateWithCString( NULL, portName.c_str(), kCFStringEncodingASCII ),
+ midiInputCallback, (void *)&inputData_, &endpoint );
+ if ( result != noErr ) {
+ errorString_ = "MidiInCore::openVirtualPort: error creating virtual OS-X MIDI destination.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ // Save our api-specific connection information.
+ data->endpoint = endpoint;
+}
+
+void MidiInCore :: closePort( void )
+{
+ if ( connected_ ) {
+ CoreMidiData *data = static_cast<CoreMidiData *> (apiData_);
+ MIDIPortDispose( data->port );
+ connected_ = false;
+ }
+}
+
+unsigned int MidiInCore :: getPortCount()
+{
+ return MIDIGetNumberOfSources();
+}
+
+// This function was submitted by Douglas Casey Tucker and apparently
+// derived largely from PortMidi.
+CFStringRef EndpointName( MIDIEndpointRef endpoint, bool isExternal )
+{
+ CFMutableStringRef result = CFStringCreateMutable( NULL, 0 );
+ CFStringRef str;
+
+ // Begin with the endpoint's name.
+ str = NULL;
+ MIDIObjectGetStringProperty( endpoint, kMIDIPropertyName, &str );
+ if ( str != NULL ) {
+ CFStringAppend( result, str );
+ CFRelease( str );
+ }
+
+ MIDIEntityRef entity = NULL;
+ MIDIEndpointGetEntity( endpoint, &entity );
+ if ( entity == 0 )
+ // probably virtual
+ return result;
+
+ if ( CFStringGetLength( result ) == 0 ) {
+ // endpoint name has zero length -- try the entity
+ str = NULL;
+ MIDIObjectGetStringProperty( entity, kMIDIPropertyName, &str );
+ if ( str != NULL ) {
+ CFStringAppend( result, str );
+ CFRelease( str );
+ }
+ }
+ // now consider the device's name
+ MIDIDeviceRef device = 0;
+ MIDIEntityGetDevice( entity, &device );
+ if ( device == 0 )
+ return result;
+
+ str = NULL;
+ MIDIObjectGetStringProperty( device, kMIDIPropertyName, &str );
+ if ( CFStringGetLength( result ) == 0 ) {
+ CFRelease( result );
+ return str;
+ }
+ if ( str != NULL ) {
+ // if an external device has only one entity, throw away
+ // the endpoint name and just use the device name
+ if ( isExternal && MIDIDeviceGetNumberOfEntities( device ) < 2 ) {
+ CFRelease( result );
+ return str;
+ } else {
+ if ( CFStringGetLength( str ) == 0 ) {
+ CFRelease( str );
+ return result;
+ }
+ // does the entity name already start with the device name?
+ // (some drivers do this though they shouldn't)
+ // if so, do not prepend
+ if ( CFStringCompareWithOptions( result, /* endpoint name */
+ str /* device name */,
+ CFRangeMake(0, CFStringGetLength( str ) ), 0 ) != kCFCompareEqualTo ) {
+ // prepend the device name to the entity name
+ if ( CFStringGetLength( result ) > 0 )
+ CFStringInsert( result, 0, CFSTR(" ") );
+ CFStringInsert( result, 0, str );
+ }
+ CFRelease( str );
+ }
+ }
+ return result;
+}
+
+// This function was submitted by Douglas Casey Tucker and apparently
+// derived largely from PortMidi.
+static CFStringRef ConnectedEndpointName( MIDIEndpointRef endpoint )
+{
+ CFMutableStringRef result = CFStringCreateMutable( NULL, 0 );
+ CFStringRef str;
+ OSStatus err;
+ int i;
+
+ // Does the endpoint have connections?
+ CFDataRef connections = NULL;
+ int nConnected = 0;
+ bool anyStrings = false;
+ err = MIDIObjectGetDataProperty( endpoint, kMIDIPropertyConnectionUniqueID, &connections );
+ if ( connections != NULL ) {
+ // It has connections, follow them
+ // Concatenate the names of all connected devices
+ nConnected = CFDataGetLength( connections ) / sizeof(MIDIUniqueID);
+ if ( nConnected ) {
+ const SInt32 *pid = (const SInt32 *)(CFDataGetBytePtr(connections));
+ for ( i=0; i<nConnected; ++i, ++pid ) {
+ MIDIUniqueID id = EndianS32_BtoN( *pid );
+ MIDIObjectRef connObject;
+ MIDIObjectType connObjectType;
+ err = MIDIObjectFindByUniqueID( id, &connObject, &connObjectType );
+ if ( err == noErr ) {
+ if ( connObjectType == kMIDIObjectType_ExternalSource ||
+ connObjectType == kMIDIObjectType_ExternalDestination ) {
+ // Connected to an external device's endpoint (10.3 and later).
+ str = EndpointName( (MIDIEndpointRef)(connObject), true );
+ } else {
+ // Connected to an external device (10.2) (or something else, catch-
+ str = NULL;
+ MIDIObjectGetStringProperty( connObject, kMIDIPropertyName, &str );
+ }
+ if ( str != NULL ) {
+ if ( anyStrings )
+ CFStringAppend( result, CFSTR(", ") );
+ else anyStrings = true;
+ CFStringAppend( result, str );
+ CFRelease( str );
+ }
+ }
+ }
+ }
+ CFRelease( connections );
+ }
+ if ( anyStrings )
+ return result;
+
+ // Here, either the endpoint had no connections, or we failed to obtain names
+ return EndpointName( endpoint, false );
+}
+
+std::string MidiInCore :: getPortName( unsigned int portNumber )
+{
+ CFStringRef nameRef;
+ MIDIEndpointRef portRef;
+ std::ostringstream ost;
+ char name[128];
+
+ std::string stringName;
+ if ( portNumber >= MIDIGetNumberOfSources() ) {
+ ost << "MidiInCore::getPortName: the 'portNumber' argument (" << portNumber << ") is invalid.";
+ errorString_ = ost.str();
+ RtMidi::error( RtError::WARNING, errorString_ );
+ //RtMidi::error( RtError::INVALID_PARAMETER, errorString_ );
+ return stringName;
+ }
+
+ portRef = MIDIGetSource( portNumber );
+ nameRef = ConnectedEndpointName(portRef);
+ CFStringGetCString( nameRef, name, sizeof(name), 0);
+ CFRelease( nameRef );
+
+ return stringName = name;
+}
+
+//*********************************************************************//
+// API: OS-X
+// Class Definitions: MidiOutCore
+//*********************************************************************//
+
+MidiOutCore :: MidiOutCore( const std::string clientName ) : MidiOutApi()
+{
+ initialize( clientName );
+}
+
+MidiOutCore :: ~MidiOutCore( void )
+{
+ // Close a connection if it exists.
+ closePort();
+
+ // Cleanup.
+ CoreMidiData *data = static_cast<CoreMidiData *> (apiData_);
+ MIDIClientDispose( data->client );
+ if ( data->endpoint ) MIDIEndpointDispose( data->endpoint );
+ delete data;
+}
+
+void MidiOutCore :: initialize( const std::string& clientName )
+{
+ // Set up our client.
+ MIDIClientRef client;
+ OSStatus result = MIDIClientCreate( CFStringCreateWithCString( NULL, clientName.c_str(), kCFStringEncodingASCII ), NULL, NULL, &client );
+ if ( result != noErr ) {
+ errorString_ = "MidiOutCore::initialize: error creating OS-X MIDI client object.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ // Save our api-specific connection information.
+ CoreMidiData *data = (CoreMidiData *) new CoreMidiData;
+ data->client = client;
+ data->endpoint = 0;
+ apiData_ = (void *) data;
+}
+
+unsigned int MidiOutCore :: getPortCount()
+{
+ return MIDIGetNumberOfDestinations();
+}
+
+std::string MidiOutCore :: getPortName( unsigned int portNumber )
+{
+ CFStringRef nameRef;
+ MIDIEndpointRef portRef;
+ std::ostringstream ost;
+ char name[128];
+
+ std::string stringName;
+ if ( portNumber >= MIDIGetNumberOfDestinations() ) {
+ ost << "MidiOutCore::getPortName: the 'portNumber' argument (" << portNumber << ") is invalid.";
+ errorString_ = ost.str();
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return stringName;
+ //RtMidi::error( RtError::INVALID_PARAMETER, errorString_ );
+ }
+
+ portRef = MIDIGetDestination( portNumber );
+ nameRef = ConnectedEndpointName(portRef);
+ CFStringGetCString( nameRef, name, sizeof(name), 0);
+ CFRelease( nameRef );
+
+ return stringName = name;
+}
+
+void MidiOutCore :: openPort( unsigned int portNumber, const std::string portName )
+{
+ if ( connected_ ) {
+ errorString_ = "MidiOutCore::openPort: a valid connection already exists!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return;
+ }
+
+ unsigned int nDest = MIDIGetNumberOfDestinations();
+ if (nDest < 1) {
+ errorString_ = "MidiOutCore::openPort: no MIDI output destinations found!";
+ RtMidi::error( RtError::NO_DEVICES_FOUND, errorString_ );
+ }
+
+ std::ostringstream ost;
+ if ( portNumber >= nDest ) {
+ ost << "MidiOutCore::openPort: the 'portNumber' argument (" << portNumber << ") is invalid.";
+ errorString_ = ost.str();
+ RtMidi::error( RtError::INVALID_PARAMETER, errorString_ );
+ }
+
+ MIDIPortRef port;
+ CoreMidiData *data = static_cast<CoreMidiData *> (apiData_);
+ OSStatus result = MIDIOutputPortCreate( data->client,
+ CFStringCreateWithCString( NULL, portName.c_str(), kCFStringEncodingASCII ),
+ &port );
+ if ( result != noErr ) {
+ MIDIClientDispose( data->client );
+ errorString_ = "MidiOutCore::openPort: error creating OS-X MIDI output port.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ // Get the desired output port identifier.
+ MIDIEndpointRef destination = MIDIGetDestination( portNumber );
+ if ( destination == 0 ) {
+ MIDIPortDispose( port );
+ MIDIClientDispose( data->client );
+ errorString_ = "MidiOutCore::openPort: error getting MIDI output destination reference.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ // Save our api-specific connection information.
+ data->port = port;
+ data->destinationId = destination;
+ connected_ = true;
+}
+
+void MidiOutCore :: closePort( void )
+{
+ if ( connected_ ) {
+ CoreMidiData *data = static_cast<CoreMidiData *> (apiData_);
+ MIDIPortDispose( data->port );
+ connected_ = false;
+ }
+}
+
+void MidiOutCore :: openVirtualPort( std::string portName )
+{
+ CoreMidiData *data = static_cast<CoreMidiData *> (apiData_);
+
+ if ( data->endpoint ) {
+ errorString_ = "MidiOutCore::openVirtualPort: a virtual output port already exists!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return;
+ }
+
+ // Create a virtual MIDI output source.
+ MIDIEndpointRef endpoint;
+ OSStatus result = MIDISourceCreate( data->client,
+ CFStringCreateWithCString( NULL, portName.c_str(), kCFStringEncodingASCII ),
+ &endpoint );
+ if ( result != noErr ) {
+ errorString_ = "MidiOutCore::initialize: error creating OS-X virtual MIDI source.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ // Save our api-specific connection information.
+ data->endpoint = endpoint;
+}
+
+char *sysexBuffer = 0;
+
+void sysexCompletionProc( MIDISysexSendRequest * sreq )
+{
+ //std::cout << "Completed SysEx send\n";
+ delete sysexBuffer;
+ sysexBuffer = 0;
+}
+
+void MidiOutCore :: sendMessage( std::vector<unsigned char> *message )
+{
+ // We use the MIDISendSysex() function to asynchronously send sysex
+ // messages. Otherwise, we use a single CoreMidi MIDIPacket.
+ unsigned int nBytes = message->size();
+ if ( nBytes == 0 ) {
+ errorString_ = "MidiOutCore::sendMessage: no data in message argument!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return;
+ }
+
+ // unsigned int packetBytes, bytesLeft = nBytes;
+ // unsigned int messageIndex = 0;
+ MIDITimeStamp timeStamp = AudioGetCurrentHostTime();
+ CoreMidiData *data = static_cast<CoreMidiData *> (apiData_);
+ OSStatus result;
+
+ if ( message->at(0) == 0xF0 ) {
+
+ while ( sysexBuffer != 0 ) usleep( 1000 ); // sleep 1 ms
+
+ sysexBuffer = new char[nBytes];
+ if ( sysexBuffer == NULL ) {
+ errorString_ = "MidiOutCore::sendMessage: error allocating sysex message memory!";
+ RtMidi::error( RtError::MEMORY_ERROR, errorString_ );
+ }
+
+ // Copy data to buffer.
+ for ( unsigned int i=0; i<nBytes; ++i ) sysexBuffer[i] = message->at(i);
+
+ data->sysexreq.destination = data->destinationId;
+ data->sysexreq.data = (Byte *)sysexBuffer;
+ data->sysexreq.bytesToSend = nBytes;
+ data->sysexreq.complete = 0;
+ data->sysexreq.completionProc = sysexCompletionProc;
+ data->sysexreq.completionRefCon = &(data->sysexreq);
+
+ result = MIDISendSysex( &(data->sysexreq) );
+ if ( result != noErr ) {
+ errorString_ = "MidiOutCore::sendMessage: error sending MIDI to virtual destinations.";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ }
+ return;
+ }
+ else if ( nBytes > 3 ) {
+ errorString_ = "MidiOutCore::sendMessage: message format problem ... not sysex but > 3 bytes?";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return;
+ }
+
+ MIDIPacketList packetList;
+ MIDIPacket *packet = MIDIPacketListInit( &packetList );
+ packet = MIDIPacketListAdd( &packetList, sizeof(packetList), packet, timeStamp, nBytes, (const Byte *) &message->at( 0 ) );
+ if ( !packet ) {
+ errorString_ = "MidiOutCore::sendMessage: could not allocate packet list";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ // Send to any destinations that may have connected to us.
+ if ( data->endpoint ) {
+ result = MIDIReceived( data->endpoint, &packetList );
+ if ( result != noErr ) {
+ errorString_ = "MidiOutCore::sendMessage: error sending MIDI to virtual destinations.";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ }
+ }
+
+ // And send to an explicit destination port if we're connected.
+ if ( connected_ ) {
+ result = MIDISend( data->port, data->destinationId, &packetList );
+ if ( result != noErr ) {
+ errorString_ = "MidiOutCore::sendMessage: error sending MIDI message to port.";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ }
+ }
+
+}
+
+#endif // __MACOSX_CORE__
+
+
+//*********************************************************************//
+// API: LINUX ALSA SEQUENCER
+//*********************************************************************//
+
+// API information found at:
+// - http://www.alsa-project.org/documentation.php#Library
+
+#if defined(__LINUX_ALSA__)
+
+// The ALSA Sequencer API is based on the use of a callback function for
+// MIDI input.
+//
+// Thanks to Pedro Lopez-Cabanillas for help with the ALSA sequencer
+// time stamps and other assorted fixes!!!
+
+// If you don't need timestamping for incoming MIDI events, define the
+// preprocessor definition AVOID_TIMESTAMPING to save resources
+// associated with the ALSA sequencer queues.
+
+#include <pthread.h>
+#include <sys/time.h>
+
+// ALSA header file.
+#include <alsa/asoundlib.h>
+
+// Global sequencer instance created when first In/Out object is
+// created, then destroyed when last In/Out is deleted.
+static snd_seq_t *s_seq = NULL;
+
+// Variable to keep track of how many ports are open.
+static unsigned int s_numPorts = 0;
+
+// The client name to use when creating the sequencer, which is
+// currently set on the first call to createSequencer.
+static std::string s_clientName = "RtMidi Client";
+
+// A structure to hold variables related to the ALSA API
+// implementation.
+struct AlsaMidiData {
+ snd_seq_t *seq;
+ unsigned int portNum;
+ int vport;
+ snd_seq_port_subscribe_t *subscription;
+ snd_midi_event_t *coder;
+ unsigned int bufferSize;
+ unsigned char *buffer;
+ pthread_t thread;
+ pthread_t dummy_thread_id;
+ unsigned long long lastTime;
+ int queue_id; // an input queue is needed to get timestamped events
+ int trigger_fds[2];
+};
+
+#define PORT_TYPE( pinfo, bits ) ((snd_seq_port_info_get_capability(pinfo) & (bits)) == (bits))
+
+snd_seq_t* createSequencer( const std::string& clientName )
+{
+ // Set up the ALSA sequencer client.
+ if ( s_seq == NULL ) {
+ int result = snd_seq_open(&s_seq, "default", SND_SEQ_OPEN_DUPLEX, SND_SEQ_NONBLOCK);
+ if ( result < 0 ) {
+ s_seq = NULL;
+ }
+ else {
+ // Set client name, use current name if given string is empty.
+ if ( clientName != "" ) {
+ s_clientName = clientName;
+ }
+ snd_seq_set_client_name( s_seq, s_clientName.c_str() );
+ }
+ }
+
+ // Increment port count.
+ s_numPorts++;
+
+ return s_seq;
+}
+
+void freeSequencer ( void )
+{
+ s_numPorts--;
+ if ( s_numPorts == 0 && s_seq != NULL ) {
+ snd_seq_close( s_seq );
+ s_seq = NULL;
+ }
+}
+
+//*********************************************************************//
+// API: LINUX ALSA
+// Class Definitions: MidiInAlsa
+//*********************************************************************//
+
+extern "C" void *alsaMidiHandler( void *ptr )
+{
+ MidiInApi::RtMidiInData *data = static_cast<MidiInApi::RtMidiInData *> (ptr);
+ AlsaMidiData *apiData = static_cast<AlsaMidiData *> (data->apiData);
+
+ long nBytes;
+ unsigned long long time, lastTime;
+ bool continueSysex = false;
+ bool doDecode = false;
+ MidiInApi::MidiMessage message;
+ int poll_fd_count;
+ struct pollfd *poll_fds;
+
+ snd_seq_event_t *ev;
+ int result;
+ apiData->bufferSize = 32;
+ result = snd_midi_event_new( 0, &apiData->coder );
+ if ( result < 0 ) {
+ data->doInput = false;
+ std::cerr << "\nMidiInAlsa::alsaMidiHandler: error initializing MIDI event parser!\n\n";
+ return 0;
+ }
+ unsigned char *buffer = (unsigned char *) malloc( apiData->bufferSize );
+ if ( buffer == NULL ) {
+ data->doInput = false;
+ snd_midi_event_free( apiData->coder );
+ apiData->coder = 0;
+ std::cerr << "\nMidiInAlsa::alsaMidiHandler: error initializing buffer memory!\n\n";
+ return 0;
+ }
+ snd_midi_event_init( apiData->coder );
+ snd_midi_event_no_status( apiData->coder, 1 ); // suppress running status messages
+
+ poll_fd_count = snd_seq_poll_descriptors_count( apiData->seq, POLLIN ) + 1;
+ poll_fds = (struct pollfd*)alloca( poll_fd_count * sizeof( struct pollfd ));
+ snd_seq_poll_descriptors( apiData->seq, poll_fds + 1, poll_fd_count - 1, POLLIN );
+ poll_fds[0].fd = apiData->trigger_fds[0];
+ poll_fds[0].events = POLLIN;
+
+ while ( data->doInput ) {
+
+ if ( snd_seq_event_input_pending( apiData->seq, 1 ) == 0 ) {
+ // No data pending
+ if ( poll( poll_fds, poll_fd_count, -1) >= 0 ) {
+ if ( poll_fds[0].revents & POLLIN ) {
+ bool dummy;
+ int res = read( poll_fds[0].fd, &dummy, sizeof(dummy) );
+ (void) res;
+ }
+ }
+ continue;
+ }
+
+ // If here, there should be data.
+ result = snd_seq_event_input( apiData->seq, &ev );
+ if ( result == -ENOSPC ) {
+ std::cerr << "\nMidiInAlsa::alsaMidiHandler: MIDI input buffer overrun!\n\n";
+ continue;
+ }
+ else if ( result <= 0 ) {
+ std::cerr << "MidiInAlsa::alsaMidiHandler: unknown MIDI input error!\n";
+ continue;
+ }
+
+ // This is a bit weird, but we now have to decode an ALSA MIDI
+ // event (back) into MIDI bytes. We'll ignore non-MIDI types.
+ if ( !continueSysex ) message.bytes.clear();
+
+ doDecode = false;
+ switch ( ev->type ) {
+
+ case SND_SEQ_EVENT_PORT_SUBSCRIBED:
+#if defined(__RTMIDI_DEBUG__)
+ std::cout << "MidiInAlsa::alsaMidiHandler: port connection made!\n";
+#endif
+ break;
+
+ case SND_SEQ_EVENT_PORT_UNSUBSCRIBED:
+#if defined(__RTMIDI_DEBUG__)
+ std::cerr << "MidiInAlsa::alsaMidiHandler: port connection has closed!\n";
+ std::cout << "sender = " << (int) ev->data.connect.sender.client << ":"
+ << (int) ev->data.connect.sender.port
+ << ", dest = " << (int) ev->data.connect.dest.client << ":"
+ << (int) ev->data.connect.dest.port
+ << std::endl;
+#endif
+ break;
+
+ case SND_SEQ_EVENT_QFRAME: // MIDI time code
+ if ( !( data->ignoreFlags & 0x02 ) ) doDecode = true;
+ break;
+
+ case SND_SEQ_EVENT_TICK: // MIDI timing tick
+ if ( !( data->ignoreFlags & 0x02 ) ) doDecode = true;
+ break;
+
+ case SND_SEQ_EVENT_SENSING: // Active sensing
+ if ( !( data->ignoreFlags & 0x04 ) ) doDecode = true;
+ break;
+
+ case SND_SEQ_EVENT_SYSEX:
+ if ( (data->ignoreFlags & 0x01) ) break;
+ if ( ev->data.ext.len > apiData->bufferSize ) {
+ apiData->bufferSize = ev->data.ext.len;
+ free( buffer );
+ buffer = (unsigned char *) malloc( apiData->bufferSize );
+ if ( buffer == NULL ) {
+ data->doInput = false;
+ std::cerr << "\nMidiInAlsa::alsaMidiHandler: error resizing buffer memory!\n\n";
+ break;
+ }
+ }
+
+ default:
+ doDecode = true;
+ }
+
+ if ( doDecode ) {
+
+ nBytes = snd_midi_event_decode( apiData->coder, buffer, apiData->bufferSize, ev );
+ if ( nBytes > 0 ) {
+ // The ALSA sequencer has a maximum buffer size for MIDI sysex
+ // events of 256 bytes. If a device sends sysex messages larger
+ // than this, they are segmented into 256 byte chunks. So,
+ // we'll watch for this and concatenate sysex chunks into a
+ // single sysex message if necessary.
+ if ( !continueSysex )
+ message.bytes.assign( buffer, &buffer[nBytes] );
+ else
+ message.bytes.insert( message.bytes.end(), buffer, &buffer[nBytes] );
+
+ continueSysex = ( ( ev->type == SND_SEQ_EVENT_SYSEX ) && ( message.bytes.back() != 0xF7 ) );
+ if ( !continueSysex ) {
+
+ // Calculate the time stamp:
+ message.timeStamp = 0.0;
+
+ // Method 1: Use the system time.
+ //(void)gettimeofday(&tv, (struct timezone *)NULL);
+ //time = (tv.tv_sec * 1000000) + tv.tv_usec;
+
+ // Method 2: Use the ALSA sequencer event time data.
+ // (thanks to Pedro Lopez-Cabanillas!).
+ time = ( ev->time.time.tv_sec * 1000000 ) + ( ev->time.time.tv_nsec/1000 );
+ lastTime = time;
+ time -= apiData->lastTime;
+ apiData->lastTime = lastTime;
+ if ( data->firstMessage == true )
+ data->firstMessage = false;
+ else
+ message.timeStamp = time * 0.000001;
+ }
+ else {
+#if defined(__RTMIDI_DEBUG__)
+ std::cerr << "\nMidiInAlsa::alsaMidiHandler: event parsing error or not a MIDI event!\n\n";
+#endif
+ }
+ }
+ }
+
+ snd_seq_free_event( ev );
+ if ( message.bytes.size() == 0 || continueSysex ) continue;
+
+ if ( data->usingCallback ) {
+ RtMidiIn::RtMidiCallback callback = (RtMidiIn::RtMidiCallback) data->userCallback;
+ callback( message.timeStamp, &message.bytes, data->userData );
+ }
+ else {
+ // As long as we haven't reached our queue size limit, push the message.
+ if ( data->queue.size < data->queue.ringSize ) {
+ data->queue.ring[data->queue.back++] = message;
+ if ( data->queue.back == data->queue.ringSize )
+ data->queue.back = 0;
+ data->queue.size++;
+ }
+ else
+ std::cerr << "\nMidiInAlsa: message queue limit reached!!\n\n";
+ }
+ }
+
+ if ( buffer ) free( buffer );
+ snd_midi_event_free( apiData->coder );
+ apiData->coder = 0;
+ apiData->thread = apiData->dummy_thread_id;
+ return 0;
+}
+
+MidiInAlsa :: MidiInAlsa( const std::string clientName, unsigned int queueSizeLimit ) : MidiInApi( queueSizeLimit )
+{
+ initialize( clientName );
+}
+
+MidiInAlsa :: ~MidiInAlsa()
+{
+ // Close a connection if it exists.
+ closePort();
+
+ // Shutdown the input thread.
+ AlsaMidiData *data = static_cast<AlsaMidiData *> (apiData_);
+ if ( inputData_.doInput ) {
+ inputData_.doInput = false;
+ int res = write( data->trigger_fds[1], &inputData_.doInput, sizeof(inputData_.doInput) );
+ (void) res;
+ if ( !pthread_equal(data->thread, data->dummy_thread_id) )
+ pthread_join( data->thread, NULL );
+ }
+
+ // Cleanup.
+ close ( data->trigger_fds[0] );
+ close ( data->trigger_fds[1] );
+ if ( data->vport >= 0 ) snd_seq_delete_port( data->seq, data->vport );
+#ifndef AVOID_TIMESTAMPING
+ snd_seq_free_queue( data->seq, data->queue_id );
+#endif
+ freeSequencer();
+ delete data;
+}
+
+void MidiInAlsa :: initialize( const std::string& clientName )
+{
+ snd_seq_t* seq = createSequencer( clientName );
+ if ( seq == NULL ) {
+ s_seq = NULL;
+ errorString_ = "MidiInAlsa::initialize: error creating ALSA sequencer client object.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ // Save our api-specific connection information.
+ AlsaMidiData *data = (AlsaMidiData *) new AlsaMidiData;
+ data->seq = seq;
+ data->portNum = -1;
+ data->vport = -1;
+ data->subscription = 0;
+ data->dummy_thread_id = pthread_self();
+ data->thread = data->dummy_thread_id;
+ data->trigger_fds[0] = -1;
+ data->trigger_fds[1] = -1;
+ apiData_ = (void *) data;
+ inputData_.apiData = (void *) data;
+
+ if ( pipe(data->trigger_fds) == -1 ) {
+ errorString_ = "MidiInAlsa::initialize: error creating pipe objects.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ // Create the input queue
+#ifndef AVOID_TIMESTAMPING
+ data->queue_id = snd_seq_alloc_named_queue(s_seq, "RtMidi Queue");
+ // Set arbitrary tempo (mm=100) and resolution (240)
+ snd_seq_queue_tempo_t *qtempo;
+ snd_seq_queue_tempo_alloca(&qtempo);
+ snd_seq_queue_tempo_set_tempo(qtempo, 600000);
+ snd_seq_queue_tempo_set_ppq(qtempo, 240);
+ snd_seq_set_queue_tempo(data->seq, data->queue_id, qtempo);
+ snd_seq_drain_output(data->seq);
+#endif
+}
+
+// This function is used to count or get the pinfo structure for a given port number.
+unsigned int portInfo( snd_seq_t *seq, snd_seq_port_info_t *pinfo, unsigned int type, int portNumber )
+{
+ snd_seq_client_info_t *cinfo;
+ int client;
+ int count = 0;
+ snd_seq_client_info_alloca( &cinfo );
+
+ snd_seq_client_info_set_client( cinfo, -1 );
+ while ( snd_seq_query_next_client( seq, cinfo ) >= 0 ) {
+ client = snd_seq_client_info_get_client( cinfo );
+ if ( client == 0 ) continue;
+ // Reset query info
+ snd_seq_port_info_set_client( pinfo, client );
+ snd_seq_port_info_set_port( pinfo, -1 );
+ while ( snd_seq_query_next_port( seq, pinfo ) >= 0 ) {
+ unsigned int atyp = snd_seq_port_info_get_type( pinfo );
+ if ( ( atyp & SND_SEQ_PORT_TYPE_MIDI_GENERIC ) == 0 ) continue;
+ unsigned int caps = snd_seq_port_info_get_capability( pinfo );
+ if ( ( caps & type ) != type ) continue;
+ if ( count == portNumber ) return 1;
+ ++count;
+ }
+ }
+
+ // If a negative portNumber was used, return the port count.
+ if ( portNumber < 0 ) return count;
+ return 0;
+}
+
+unsigned int MidiInAlsa :: getPortCount()
+{
+ snd_seq_port_info_t *pinfo;
+ snd_seq_port_info_alloca( &pinfo );
+
+ AlsaMidiData *data = static_cast<AlsaMidiData *> (apiData_);
+ return portInfo( data->seq, pinfo, SND_SEQ_PORT_CAP_READ|SND_SEQ_PORT_CAP_SUBS_READ, -1 );
+}
+
+std::string MidiInAlsa :: getPortName( unsigned int portNumber )
+{
+ snd_seq_client_info_t *cinfo;
+ snd_seq_port_info_t *pinfo;
+ snd_seq_client_info_alloca( &cinfo );
+ snd_seq_port_info_alloca( &pinfo );
+
+ std::string stringName;
+ AlsaMidiData *data = static_cast<AlsaMidiData *> (apiData_);
+ if ( portInfo( data->seq, pinfo, SND_SEQ_PORT_CAP_READ|SND_SEQ_PORT_CAP_SUBS_READ, (int) portNumber ) ) {
+ int cnum = snd_seq_port_info_get_client( pinfo );
+ snd_seq_get_any_client_info( data->seq, cnum, cinfo );
+ std::ostringstream os;
+ os << snd_seq_client_info_get_name( cinfo );
+ os << " "; // GO: These lines added to make sure devices are listed
+ os << snd_seq_port_info_get_client( pinfo ); // GO: with full portnames added to ensure individual device names
+ os << ":";
+ os << snd_seq_port_info_get_port( pinfo );
+ stringName = os.str();
+ return stringName;
+ }
+
+ // If we get here, we didn't find a match.
+ errorString_ = "MidiInAlsa::getPortName: error looking for port name!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return stringName;
+ //RtMidi::error( RtError::INVALID_PARAMETER, errorString_ );
+}
+
+void MidiInAlsa :: openPort( unsigned int portNumber, const std::string portName )
+{
+ if ( connected_ ) {
+ errorString_ = "MidiInAlsa::openPort: a valid connection already exists!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return;
+ }
+
+ unsigned int nSrc = this->getPortCount();
+ if (nSrc < 1) {
+ errorString_ = "MidiInAlsa::openPort: no MIDI input sources found!";
+ RtMidi::error( RtError::NO_DEVICES_FOUND, errorString_ );
+ }
+
+ snd_seq_port_info_t *pinfo;
+ snd_seq_port_info_alloca( &pinfo );
+ std::ostringstream ost;
+ AlsaMidiData *data = static_cast<AlsaMidiData *> (apiData_);
+ if ( portInfo( data->seq, pinfo, SND_SEQ_PORT_CAP_READ|SND_SEQ_PORT_CAP_SUBS_READ, (int) portNumber ) == 0 ) {
+ ost << "MidiInAlsa::openPort: the 'portNumber' argument (" << portNumber << ") is invalid.";
+ errorString_ = ost.str();
+ RtMidi::error( RtError::INVALID_PARAMETER, errorString_ );
+ }
+
+
+ snd_seq_addr_t sender, receiver;
+ sender.client = snd_seq_port_info_get_client( pinfo );
+ sender.port = snd_seq_port_info_get_port( pinfo );
+ receiver.client = snd_seq_client_id( data->seq );
+ if ( data->vport < 0 ) {
+ snd_seq_port_info_set_client( pinfo, 0 );
+ snd_seq_port_info_set_port( pinfo, 0 );
+ snd_seq_port_info_set_capability( pinfo,
+ SND_SEQ_PORT_CAP_WRITE |
+ SND_SEQ_PORT_CAP_SUBS_WRITE );
+ snd_seq_port_info_set_type( pinfo,
+ SND_SEQ_PORT_TYPE_MIDI_GENERIC |
+ SND_SEQ_PORT_TYPE_APPLICATION );
+ snd_seq_port_info_set_midi_channels(pinfo, 16);
+#ifndef AVOID_TIMESTAMPING
+ snd_seq_port_info_set_timestamping(pinfo, 1);
+ snd_seq_port_info_set_timestamp_real(pinfo, 1);
+ snd_seq_port_info_set_timestamp_queue(pinfo, data->queue_id);
+#endif
+ snd_seq_port_info_set_name(pinfo, portName.c_str() );
+ data->vport = snd_seq_create_port(data->seq, pinfo);
+
+ if ( data->vport < 0 ) {
+ errorString_ = "MidiInAlsa::openPort: ALSA error creating input port.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+ }
+
+ receiver.port = data->vport;
+
+ if ( !data->subscription ) {
+ // Make subscription
+ if (snd_seq_port_subscribe_malloc( &data->subscription ) < 0) {
+ errorString_ = "MidiInAlsa::openPort: ALSA error allocation port subscription.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+ snd_seq_port_subscribe_set_sender(data->subscription, &sender);
+ snd_seq_port_subscribe_set_dest(data->subscription, &receiver);
+ if ( snd_seq_subscribe_port(data->seq, data->subscription) ) {
+ snd_seq_port_subscribe_free( data->subscription );
+ data->subscription = 0;
+ errorString_ = "MidiInAlsa::openPort: ALSA error making port connection.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+ }
+
+ if ( inputData_.doInput == false ) {
+ // Start the input queue
+#ifndef AVOID_TIMESTAMPING
+ snd_seq_start_queue( data->seq, data->queue_id, NULL );
+ snd_seq_drain_output( data->seq );
+#endif
+ // Start our MIDI input thread.
+ pthread_attr_t attr;
+ pthread_attr_init(&attr);
+ pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE);
+ pthread_attr_setschedpolicy(&attr, SCHED_OTHER);
+
+ inputData_.doInput = true;
+ int err = pthread_create(&data->thread, &attr, alsaMidiHandler, &inputData_);
+ pthread_attr_destroy(&attr);
+ if ( err ) {
+ snd_seq_unsubscribe_port( data->seq, data->subscription );
+ snd_seq_port_subscribe_free( data->subscription );
+ data->subscription = 0;
+ inputData_.doInput = false;
+ errorString_ = "MidiInAlsa::openPort: error starting MIDI input thread!";
+ RtMidi::error( RtError::THREAD_ERROR, errorString_ );
+ }
+ }
+
+ connected_ = true;
+}
+
+void MidiInAlsa :: openVirtualPort( std::string portName )
+{
+ AlsaMidiData *data = static_cast<AlsaMidiData *> (apiData_);
+ if ( data->vport < 0 ) {
+ snd_seq_port_info_t *pinfo;
+ snd_seq_port_info_alloca( &pinfo );
+ snd_seq_port_info_set_capability( pinfo,
+ SND_SEQ_PORT_CAP_WRITE |
+ SND_SEQ_PORT_CAP_SUBS_WRITE );
+ snd_seq_port_info_set_type( pinfo,
+ SND_SEQ_PORT_TYPE_MIDI_GENERIC |
+ SND_SEQ_PORT_TYPE_APPLICATION );
+ snd_seq_port_info_set_midi_channels(pinfo, 16);
+#ifndef AVOID_TIMESTAMPING
+ snd_seq_port_info_set_timestamping(pinfo, 1);
+ snd_seq_port_info_set_timestamp_real(pinfo, 1);
+ snd_seq_port_info_set_timestamp_queue(pinfo, data->queue_id);
+#endif
+ snd_seq_port_info_set_name(pinfo, portName.c_str());
+ data->vport = snd_seq_create_port(data->seq, pinfo);
+
+ if ( data->vport < 0 ) {
+ errorString_ = "MidiInAlsa::openVirtualPort: ALSA error creating virtual port.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+ }
+
+ if ( inputData_.doInput == false ) {
+ // Wait for old thread to stop, if still running
+ if ( !pthread_equal(data->thread, data->dummy_thread_id) )
+ pthread_join( data->thread, NULL );
+
+ // Start the input queue
+#ifndef AVOID_TIMESTAMPING
+ snd_seq_start_queue( data->seq, data->queue_id, NULL );
+ snd_seq_drain_output( data->seq );
+#endif
+ // Start our MIDI input thread.
+ pthread_attr_t attr;
+ pthread_attr_init(&attr);
+ pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_JOINABLE);
+ pthread_attr_setschedpolicy(&attr, SCHED_OTHER);
+
+ inputData_.doInput = true;
+ int err = pthread_create(&data->thread, &attr, alsaMidiHandler, &inputData_);
+ pthread_attr_destroy(&attr);
+ if ( err ) {
+ if ( data->subscription ) {
+ snd_seq_unsubscribe_port( data->seq, data->subscription );
+ snd_seq_port_subscribe_free( data->subscription );
+ data->subscription = 0;
+ }
+ inputData_.doInput = false;
+ errorString_ = "MidiInAlsa::openPort: error starting MIDI input thread!";
+ RtMidi::error( RtError::THREAD_ERROR, errorString_ );
+ }
+ }
+}
+
+void MidiInAlsa :: closePort( void )
+{
+ AlsaMidiData *data = static_cast<AlsaMidiData *> (apiData_);
+
+ if ( connected_ ) {
+ if ( data->subscription ) {
+ snd_seq_unsubscribe_port( data->seq, data->subscription );
+ snd_seq_port_subscribe_free( data->subscription );
+ data->subscription = 0;
+ }
+ // Stop the input queue
+#ifndef AVOID_TIMESTAMPING
+ snd_seq_stop_queue( data->seq, data->queue_id, NULL );
+ snd_seq_drain_output( data->seq );
+#endif
+ connected_ = false;
+ }
+
+ // Stop thread to avoid triggering the callback, while the port is intended to be closed
+ if ( inputData_.doInput ) {
+ inputData_.doInput = false;
+ int res = write( data->trigger_fds[1], &inputData_.doInput, sizeof(inputData_.doInput) );
+ (void) res;
+ if ( !pthread_equal(data->thread, data->dummy_thread_id) )
+ pthread_join( data->thread, NULL );
+ }
+}
+
+//*********************************************************************//
+// API: LINUX ALSA
+// Class Definitions: MidiOutAlsa
+//*********************************************************************//
+
+MidiOutAlsa :: MidiOutAlsa( const std::string clientName ) : MidiOutApi()
+{
+ initialize( clientName );
+}
+
+MidiOutAlsa :: ~MidiOutAlsa()
+{
+ // Close a connection if it exists.
+ closePort();
+
+ // Cleanup.
+ AlsaMidiData *data = static_cast<AlsaMidiData *> (apiData_);
+ if ( data->vport >= 0 ) snd_seq_delete_port( data->seq, data->vport );
+ if ( data->coder ) snd_midi_event_free( data->coder );
+ if ( data->buffer ) free( data->buffer );
+ freeSequencer();
+ delete data;
+}
+
+void MidiOutAlsa :: initialize( const std::string& clientName )
+{
+ snd_seq_t* seq = createSequencer( clientName );
+ if ( seq == NULL ) {
+ s_seq = NULL;
+ errorString_ = "MidiOutAlsa::initialize: error creating ALSA sequencer client object.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ // Save our api-specific connection information.
+ AlsaMidiData *data = (AlsaMidiData *) new AlsaMidiData;
+ data->seq = seq;
+ data->portNum = -1;
+ data->vport = -1;
+ data->bufferSize = 32;
+ data->coder = 0;
+ data->buffer = 0;
+ int result = snd_midi_event_new( data->bufferSize, &data->coder );
+ if ( result < 0 ) {
+ delete data;
+ errorString_ = "MidiOutAlsa::initialize: error initializing MIDI event parser!\n\n";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+ data->buffer = (unsigned char *) malloc( data->bufferSize );
+ if ( data->buffer == NULL ) {
+ delete data;
+ errorString_ = "MidiOutAlsa::initialize: error allocating buffer memory!\n\n";
+ RtMidi::error( RtError::MEMORY_ERROR, errorString_ );
+ }
+ snd_midi_event_init( data->coder );
+ apiData_ = (void *) data;
+}
+
+unsigned int MidiOutAlsa :: getPortCount()
+{
+ snd_seq_port_info_t *pinfo;
+ snd_seq_port_info_alloca( &pinfo );
+
+ AlsaMidiData *data = static_cast<AlsaMidiData *> (apiData_);
+ return portInfo( data->seq, pinfo, SND_SEQ_PORT_CAP_WRITE|SND_SEQ_PORT_CAP_SUBS_WRITE, -1 );
+}
+
+std::string MidiOutAlsa :: getPortName( unsigned int portNumber )
+{
+ snd_seq_client_info_t *cinfo;
+ snd_seq_port_info_t *pinfo;
+ snd_seq_client_info_alloca( &cinfo );
+ snd_seq_port_info_alloca( &pinfo );
+
+ std::string stringName;
+ AlsaMidiData *data = static_cast<AlsaMidiData *> (apiData_);
+ if ( portInfo( data->seq, pinfo, SND_SEQ_PORT_CAP_WRITE|SND_SEQ_PORT_CAP_SUBS_WRITE, (int) portNumber ) ) {
+ int cnum = snd_seq_port_info_get_client(pinfo);
+ snd_seq_get_any_client_info( data->seq, cnum, cinfo );
+ std::ostringstream os;
+ os << snd_seq_client_info_get_name(cinfo);
+ os << ":";
+ os << snd_seq_port_info_get_port(pinfo);
+ stringName = os.str();
+ return stringName;
+ }
+
+ // If we get here, we didn't find a match.
+ errorString_ = "MidiOutAlsa::getPortName: error looking for port name!";
+ //RtMidi::error( RtError::INVALID_PARAMETER, errorString_ );
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return stringName;
+}
+
+void MidiOutAlsa :: openPort( unsigned int portNumber, const std::string portName )
+{
+ if ( connected_ ) {
+ errorString_ = "MidiOutAlsa::openPort: a valid connection already exists!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return;
+ }
+
+ unsigned int nSrc = this->getPortCount();
+ if (nSrc < 1) {
+ errorString_ = "MidiOutAlsa::openPort: no MIDI output sources found!";
+ RtMidi::error( RtError::NO_DEVICES_FOUND, errorString_ );
+ }
+
+ snd_seq_port_info_t *pinfo;
+ snd_seq_port_info_alloca( &pinfo );
+ std::ostringstream ost;
+ AlsaMidiData *data = static_cast<AlsaMidiData *> (apiData_);
+ if ( portInfo( data->seq, pinfo, SND_SEQ_PORT_CAP_WRITE|SND_SEQ_PORT_CAP_SUBS_WRITE, (int) portNumber ) == 0 ) {
+ ost << "MidiOutAlsa::openPort: the 'portNumber' argument (" << portNumber << ") is invalid.";
+ errorString_ = ost.str();
+ RtMidi::error( RtError::INVALID_PARAMETER, errorString_ );
+ }
+
+ snd_seq_addr_t sender, receiver;
+ receiver.client = snd_seq_port_info_get_client( pinfo );
+ receiver.port = snd_seq_port_info_get_port( pinfo );
+ sender.client = snd_seq_client_id( data->seq );
+
+ if ( data->vport < 0 ) {
+ data->vport = snd_seq_create_simple_port( data->seq, portName.c_str(),
+ SND_SEQ_PORT_CAP_READ|SND_SEQ_PORT_CAP_SUBS_READ,
+ SND_SEQ_PORT_TYPE_MIDI_GENERIC|SND_SEQ_PORT_TYPE_APPLICATION );
+ if ( data->vport < 0 ) {
+ errorString_ = "MidiOutAlsa::openPort: ALSA error creating output port.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+ }
+
+ sender.port = data->vport;
+
+ // Make subscription
+ if (snd_seq_port_subscribe_malloc( &data->subscription ) < 0) {
+ snd_seq_port_subscribe_free( data->subscription );
+ errorString_ = "MidiOutAlsa::openPort: error allocation port subscribtion.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+ snd_seq_port_subscribe_set_sender(data->subscription, &sender);
+ snd_seq_port_subscribe_set_dest(data->subscription, &receiver);
+ snd_seq_port_subscribe_set_time_update(data->subscription, 1);
+ snd_seq_port_subscribe_set_time_real(data->subscription, 1);
+ if ( snd_seq_subscribe_port(data->seq, data->subscription) ) {
+ snd_seq_port_subscribe_free( data->subscription );
+ errorString_ = "MidiOutAlsa::openPort: ALSA error making port connection.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ connected_ = true;
+}
+
+void MidiOutAlsa :: closePort( void )
+{
+ if ( connected_ ) {
+ AlsaMidiData *data = static_cast<AlsaMidiData *> (apiData_);
+ snd_seq_unsubscribe_port( data->seq, data->subscription );
+ snd_seq_port_subscribe_free( data->subscription );
+ connected_ = false;
+ }
+}
+
+void MidiOutAlsa :: openVirtualPort( std::string portName )
+{
+ AlsaMidiData *data = static_cast<AlsaMidiData *> (apiData_);
+ if ( data->vport < 0 ) {
+ data->vport = snd_seq_create_simple_port( data->seq, portName.c_str(),
+ SND_SEQ_PORT_CAP_READ|SND_SEQ_PORT_CAP_SUBS_READ,
+ SND_SEQ_PORT_TYPE_MIDI_GENERIC|SND_SEQ_PORT_TYPE_APPLICATION );
+
+ if ( data->vport < 0 ) {
+ errorString_ = "MidiOutAlsa::openVirtualPort: ALSA error creating virtual port.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+ }
+}
+
+void MidiOutAlsa :: sendMessage( std::vector<unsigned char> *message )
+{
+ int result;
+ AlsaMidiData *data = static_cast<AlsaMidiData *> (apiData_);
+ unsigned int nBytes = message->size();
+ if ( nBytes > data->bufferSize ) {
+ data->bufferSize = nBytes;
+ result = snd_midi_event_resize_buffer ( data->coder, nBytes);
+ if ( result != 0 ) {
+ errorString_ = "MidiOutAlsa::sendMessage: ALSA error resizing MIDI event buffer.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+ free (data->buffer);
+ data->buffer = (unsigned char *) malloc( data->bufferSize );
+ if ( data->buffer == NULL ) {
+ errorString_ = "MidiOutAlsa::initialize: error allocating buffer memory!\n\n";
+ RtMidi::error( RtError::MEMORY_ERROR, errorString_ );
+ }
+ }
+
+ snd_seq_event_t ev;
+ snd_seq_ev_clear(&ev);
+ snd_seq_ev_set_source(&ev, data->vport);
+ snd_seq_ev_set_subs(&ev);
+ snd_seq_ev_set_direct(&ev);
+ for ( unsigned int i=0; i<nBytes; ++i ) data->buffer[i] = message->at(i);
+ result = snd_midi_event_encode( data->coder, data->buffer, (long)nBytes, &ev );
+ if ( result < (int)nBytes ) {
+ errorString_ = "MidiOutAlsa::sendMessage: event parsing error!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return;
+ }
+
+ // Send the event.
+ result = snd_seq_event_output(data->seq, &ev);
+ if ( result < 0 ) {
+ errorString_ = "MidiOutAlsa::sendMessage: error sending MIDI message to port.";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ }
+ snd_seq_drain_output(data->seq);
+}
+
+#endif // __LINUX_ALSA__
+
+
+//*********************************************************************//
+// API: Windows Multimedia Library (MM)
+//*********************************************************************//
+
+// API information deciphered from:
+// - http://msdn.microsoft.com/library/default.asp?url=/library/en-us/multimed/htm/_win32_midi_reference.asp
+
+// Thanks to Jean-Baptiste Berruchon for the sysex code.
+
+#if defined(__WINDOWS_MM__)
+
+// The Windows MM API is based on the use of a callback function for
+// MIDI input. We convert the system specific time stamps to delta
+// time values.
+
+// Windows MM MIDI header files.
+#include <windows.h>
+#include <mmsystem.h>
+
+#define RT_SYSEX_BUFFER_SIZE 1024
+#define RT_SYSEX_BUFFER_COUNT 4
+
+// A structure to hold variables related to the CoreMIDI API
+// implementation.
+struct WinMidiData {
+ HMIDIIN inHandle; // Handle to Midi Input Device
+ HMIDIOUT outHandle; // Handle to Midi Output Device
+ DWORD lastTime;
+ MidiInApi::MidiMessage message;
+ LPMIDIHDR sysexBuffer[RT_SYSEX_BUFFER_COUNT];
+};
+
+//*********************************************************************//
+// API: Windows MM
+// Class Definitions: MidiInWinMM
+//*********************************************************************//
+
+static void CALLBACK midiInputCallback( HMIDIIN hmin,
+ UINT inputStatus,
+ DWORD_PTR instancePtr,
+ DWORD_PTR midiMessage,
+ DWORD timestamp )
+{
+ if ( inputStatus != MIM_DATA && inputStatus != MIM_LONGDATA && inputStatus != MIM_LONGERROR ) return;
+
+ //MidiInApi::RtMidiInData *data = static_cast<MidiInApi::RtMidiInData *> (instancePtr);
+ MidiInApi::RtMidiInData *data = (MidiInApi::RtMidiInData *)instancePtr;
+ WinMidiData *apiData = static_cast<WinMidiData *> (data->apiData);
+
+ // Calculate time stamp.
+ if ( data->firstMessage == true ) {
+ apiData->message.timeStamp = 0.0;
+ data->firstMessage = false;
+ }
+ else apiData->message.timeStamp = (double) ( timestamp - apiData->lastTime ) * 0.001;
+ apiData->lastTime = timestamp;
+
+ if ( inputStatus == MIM_DATA ) { // Channel or system message
+
+ // Make sure the first byte is a status byte.
+ unsigned char status = (unsigned char) (midiMessage & 0x000000FF);
+ if ( !(status & 0x80) ) return;
+
+ // Determine the number of bytes in the MIDI message.
+ unsigned short nBytes = 1;
+ if ( status < 0xC0 ) nBytes = 3;
+ else if ( status < 0xE0 ) nBytes = 2;
+ else if ( status < 0xF0 ) nBytes = 3;
+ else if ( status == 0xF1 ) {
+ if ( data->ignoreFlags & 0x02 ) return;
+ else nBytes = 2;
+ }
+ else if ( status == 0xF2 ) nBytes = 3;
+ else if ( status == 0xF3 ) nBytes = 2;
+ else if ( status == 0xF8 && (data->ignoreFlags & 0x02) ) {
+ // A MIDI timing tick message and we're ignoring it.
+ return;
+ }
+ else if ( status == 0xFE && (data->ignoreFlags & 0x04) ) {
+ // A MIDI active sensing message and we're ignoring it.
+ return;
+ }
+
+ // Copy bytes to our MIDI message.
+ unsigned char *ptr = (unsigned char *) &midiMessage;
+ for ( int i=0; i<nBytes; ++i ) apiData->message.bytes.push_back( *ptr++ );
+ }
+ else { // Sysex message ( MIM_LONGDATA or MIM_LONGERROR )
+ MIDIHDR *sysex = ( MIDIHDR *) midiMessage;
+ if ( !( data->ignoreFlags & 0x01 ) && inputStatus != MIM_LONGERROR ) {
+ // Sysex message and we're not ignoring it
+ for ( int i=0; i<(int)sysex->dwBytesRecorded; ++i )
+ apiData->message.bytes.push_back( sysex->lpData[i] );
+ }
+
+ // The WinMM API requires that the sysex buffer be requeued after
+ // input of each sysex message. Even if we are ignoring sysex
+ // messages, we still need to requeue the buffer in case the user
+ // decides to not ignore sysex messages in the future. However,
+ // it seems that WinMM calls this function with an empty sysex
+ // buffer when an application closes and in this case, we should
+ // avoid requeueing it, else the computer suddenly reboots after
+ // one or two minutes.
+ if ( apiData->sysexBuffer[sysex->dwUser]->dwBytesRecorded > 0 ) {
+ //if ( sysex->dwBytesRecorded > 0 ) {
+ MMRESULT result = midiInAddBuffer( apiData->inHandle, apiData->sysexBuffer[sysex->dwUser], sizeof(MIDIHDR) );
+ if ( result != MMSYSERR_NOERROR )
+ std::cerr << "\nRtMidiIn::midiInputCallback: error sending sysex to Midi device!!\n\n";
+
+ if ( data->ignoreFlags & 0x01 ) return;
+ }
+ else return;
+ }
+
+ if ( data->usingCallback ) {
+ RtMidiIn::RtMidiCallback callback = (RtMidiIn::RtMidiCallback) data->userCallback;
+ callback( apiData->message.timeStamp, &apiData->message.bytes, data->userData );
+ }
+ else {
+ // As long as we haven't reached our queue size limit, push the message.
+ if ( data->queue.size < data->queue.ringSize ) {
+ data->queue.ring[data->queue.back++] = apiData->message;
+ if ( data->queue.back == data->queue.ringSize )
+ data->queue.back = 0;
+ data->queue.size++;
+ }
+ else
+ std::cerr << "\nRtMidiIn: message queue limit reached!!\n\n";
+ }
+
+ // Clear the vector for the next input message.
+ apiData->message.bytes.clear();
+}
+
+MidiInWinMM :: MidiInWinMM( const std::string clientName, unsigned int queueSizeLimit ) : MidiInApi( queueSizeLimit )
+{
+ initialize( clientName );
+}
+
+MidiInWinMM :: ~MidiInWinMM()
+{
+ // Close a connection if it exists.
+ closePort();
+
+ // Cleanup.
+ WinMidiData *data = static_cast<WinMidiData *> (apiData_);
+ delete data;
+}
+
+void MidiInWinMM :: initialize( const std::string& /*clientName*/ )
+{
+ // We'll issue a warning here if no devices are available but not
+ // throw an error since the user can plugin something later.
+ unsigned int nDevices = midiInGetNumDevs();
+ if ( nDevices == 0 ) {
+ errorString_ = "MidiInWinMM::initialize: no MIDI input devices currently available.";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ }
+
+ // Save our api-specific connection information.
+ WinMidiData *data = (WinMidiData *) new WinMidiData;
+ apiData_ = (void *) data;
+ inputData_.apiData = (void *) data;
+ data->message.bytes.clear(); // needs to be empty for first input message
+}
+
+void MidiInWinMM :: openPort( unsigned int portNumber, const std::string /*portName*/ )
+{
+ if ( connected_ ) {
+ errorString_ = "MidiInWinMM::openPort: a valid connection already exists!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return;
+ }
+
+ unsigned int nDevices = midiInGetNumDevs();
+ if (nDevices == 0) {
+ errorString_ = "MidiInWinMM::openPort: no MIDI input sources found!";
+ RtMidi::error( RtError::NO_DEVICES_FOUND, errorString_ );
+ }
+
+ std::ostringstream ost;
+ if ( portNumber >= nDevices ) {
+ ost << "MidiInWinMM::openPort: the 'portNumber' argument (" << portNumber << ") is invalid.";
+ errorString_ = ost.str();
+ RtMidi::error( RtError::INVALID_PARAMETER, errorString_ );
+ }
+
+ WinMidiData *data = static_cast<WinMidiData *> (apiData_);
+ MMRESULT result = midiInOpen( &data->inHandle,
+ portNumber,
+ (DWORD_PTR)&midiInputCallback,
+ (DWORD_PTR)&inputData_,
+ CALLBACK_FUNCTION );
+ if ( result != MMSYSERR_NOERROR ) {
+ errorString_ = "MidiInWinMM::openPort: error creating Windows MM MIDI input port.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ // Allocate and init the sysex buffers.
+ for ( int i=0; i<RT_SYSEX_BUFFER_COUNT; ++i ) {
+ data->sysexBuffer[i] = (MIDIHDR*) new char[ sizeof(MIDIHDR) ];
+ data->sysexBuffer[i]->lpData = new char[ RT_SYSEX_BUFFER_SIZE ];
+ data->sysexBuffer[i]->dwBufferLength = RT_SYSEX_BUFFER_SIZE;
+ data->sysexBuffer[i]->dwUser = i; // We use the dwUser parameter as buffer indicator
+ data->sysexBuffer[i]->dwFlags = 0;
+
+ result = midiInPrepareHeader( data->inHandle, data->sysexBuffer[i], sizeof(MIDIHDR) );
+ if ( result != MMSYSERR_NOERROR ) {
+ midiInClose( data->inHandle );
+ errorString_ = "MidiInWinMM::openPort: error starting Windows MM MIDI input port (PrepareHeader).";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ // Register the buffer.
+ result = midiInAddBuffer( data->inHandle, data->sysexBuffer[i], sizeof(MIDIHDR) );
+ if ( result != MMSYSERR_NOERROR ) {
+ midiInClose( data->inHandle );
+ errorString_ = "MidiInWinMM::openPort: error starting Windows MM MIDI input port (AddBuffer).";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+ }
+
+ result = midiInStart( data->inHandle );
+ if ( result != MMSYSERR_NOERROR ) {
+ midiInClose( data->inHandle );
+ errorString_ = "MidiInWinMM::openPort: error starting Windows MM MIDI input port.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ connected_ = true;
+}
+
+void MidiInWinMM :: openVirtualPort( std::string portName )
+{
+ // This function cannot be implemented for the Windows MM MIDI API.
+ errorString_ = "MidiInWinMM::openVirtualPort: cannot be implemented in Windows MM MIDI API!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+}
+
+void MidiInWinMM :: closePort( void )
+{
+ if ( connected_ ) {
+ WinMidiData *data = static_cast<WinMidiData *> (apiData_);
+ midiInReset( data->inHandle );
+ midiInStop( data->inHandle );
+
+ for ( int i=0; i<RT_SYSEX_BUFFER_COUNT; ++i ) {
+ int result = midiInUnprepareHeader(data->inHandle, data->sysexBuffer[i], sizeof(MIDIHDR));
+ delete [] data->sysexBuffer[i]->lpData;
+ delete [] data->sysexBuffer[i];
+ if ( result != MMSYSERR_NOERROR ) {
+ midiInClose( data->inHandle );
+ errorString_ = "MidiInWinMM::openPort: error closing Windows MM MIDI input port (midiInUnprepareHeader).";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+ }
+
+ midiInClose( data->inHandle );
+ connected_ = false;
+ }
+}
+
+unsigned int MidiInWinMM :: getPortCount()
+{
+ return midiInGetNumDevs();
+}
+
+std::string MidiInWinMM :: getPortName( unsigned int portNumber )
+{
+ std::string stringName;
+ unsigned int nDevices = midiInGetNumDevs();
+ if ( portNumber >= nDevices ) {
+ std::ostringstream ost;
+ ost << "MidiInWinMM::getPortName: the 'portNumber' argument (" << portNumber << ") is invalid.";
+ errorString_ = ost.str();
+ //RtMidi::error( RtError::INVALID_PARAMETER, errorString_ );
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return stringName;
+ }
+
+ MIDIINCAPS deviceCaps;
+ midiInGetDevCaps( portNumber, &deviceCaps, sizeof(MIDIINCAPS));
+
+#if defined( UNICODE ) || defined( _UNICODE )
+ int length = WideCharToMultiByte(CP_UTF8, 0, deviceCaps.szPname, -1, NULL, 0, NULL, NULL);
+ stringName.assign( length, 0 );
+ length = WideCharToMultiByte(CP_UTF8, 0, deviceCaps.szPname, wcslen(deviceCaps.szPname), &stringName[0], length, NULL, NULL);
+#else
+ stringName = std::string( deviceCaps.szPname );
+#endif
+
+ // Next lines added to add the portNumber to the name so that
+ // the device's names are sure to be listed with individual names
+ // even when they have the same brand name
+ std::ostringstream os;
+ os << " ";
+ os << portNumber;
+ stringName += os.str();
+
+ return stringName;
+}
+
+//*********************************************************************//
+// API: Windows MM
+// Class Definitions: MidiOutWinMM
+//*********************************************************************//
+
+MidiOutWinMM :: MidiOutWinMM( const std::string clientName ) : MidiOutApi()
+{
+ initialize( clientName );
+}
+
+MidiOutWinMM :: ~MidiOutWinMM()
+{
+ // Close a connection if it exists.
+ closePort();
+
+ // Cleanup.
+ WinMidiData *data = static_cast<WinMidiData *> (apiData_);
+ delete data;
+}
+
+void MidiOutWinMM :: initialize( const std::string& /*clientName*/ )
+{
+ // We'll issue a warning here if no devices are available but not
+ // throw an error since the user can plug something in later.
+ unsigned int nDevices = midiOutGetNumDevs();
+ if ( nDevices == 0 ) {
+ errorString_ = "MidiOutWinMM::initialize: no MIDI output devices currently available.";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ }
+
+ // Save our api-specific connection information.
+ WinMidiData *data = (WinMidiData *) new WinMidiData;
+ apiData_ = (void *) data;
+}
+
+unsigned int MidiOutWinMM :: getPortCount()
+{
+ return midiOutGetNumDevs();
+}
+
+std::string MidiOutWinMM :: getPortName( unsigned int portNumber )
+{
+ std::string stringName;
+ unsigned int nDevices = midiOutGetNumDevs();
+ if ( portNumber >= nDevices ) {
+ std::ostringstream ost;
+ ost << "MidiOutWinMM::getPortName: the 'portNumber' argument (" << portNumber << ") is invalid.";
+ errorString_ = ost.str();
+ //RtMidi::error( RtError::INVALID_PARAMETER, errorString_ );
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return stringName;
+ }
+
+ MIDIOUTCAPS deviceCaps;
+ midiOutGetDevCaps( portNumber, &deviceCaps, sizeof(MIDIOUTCAPS));
+
+#if defined( UNICODE ) || defined( _UNICODE )
+ int length = WideCharToMultiByte(CP_UTF8, 0, deviceCaps.szPname, -1, NULL, 0, NULL, NULL);
+ stringName.assign( length, 0 );
+ length = WideCharToMultiByte(CP_UTF8, 0, deviceCaps.szPname, wcslen(deviceCaps.szPname), &stringName[0], length, NULL, NULL);
+#else
+ stringName = std::string( deviceCaps.szPname );
+#endif
+
+ return stringName;
+}
+
+void MidiOutWinMM :: openPort( unsigned int portNumber, const std::string /*portName*/ )
+{
+ if ( connected_ ) {
+ errorString_ = "MidiOutWinMM::openPort: a valid connection already exists!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return;
+ }
+
+ unsigned int nDevices = midiOutGetNumDevs();
+ if (nDevices < 1) {
+ errorString_ = "MidiOutWinMM::openPort: no MIDI output destinations found!";
+ RtMidi::error( RtError::NO_DEVICES_FOUND, errorString_ );
+ }
+
+ std::ostringstream ost;
+ if ( portNumber >= nDevices ) {
+ ost << "MidiOutWinMM::openPort: the 'portNumber' argument (" << portNumber << ") is invalid.";
+ errorString_ = ost.str();
+ RtMidi::error( RtError::INVALID_PARAMETER, errorString_ );
+ }
+
+ WinMidiData *data = static_cast<WinMidiData *> (apiData_);
+ MMRESULT result = midiOutOpen( &data->outHandle,
+ portNumber,
+ (DWORD)NULL,
+ (DWORD)NULL,
+ CALLBACK_NULL );
+ if ( result != MMSYSERR_NOERROR ) {
+ errorString_ = "MidiOutWinMM::openPort: error creating Windows MM MIDI output port.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ connected_ = true;
+}
+
+void MidiOutWinMM :: closePort( void )
+{
+ if ( connected_ ) {
+ WinMidiData *data = static_cast<WinMidiData *> (apiData_);
+ midiOutReset( data->outHandle );
+ midiOutClose( data->outHandle );
+ connected_ = false;
+ }
+}
+
+void MidiOutWinMM :: openVirtualPort( std::string portName )
+{
+ // This function cannot be implemented for the Windows MM MIDI API.
+ errorString_ = "MidiOutWinMM::openVirtualPort: cannot be implemented in Windows MM MIDI API!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+}
+
+void MidiOutWinMM :: sendMessage( std::vector<unsigned char> *message )
+{
+ unsigned int nBytes = static_cast<unsigned int>(message->size());
+ if ( nBytes == 0 ) {
+ errorString_ = "MidiOutWinMM::sendMessage: message argument is empty!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return;
+ }
+
+ MMRESULT result;
+ WinMidiData *data = static_cast<WinMidiData *> (apiData_);
+ if ( message->at(0) == 0xF0 ) { // Sysex message
+
+ // Allocate buffer for sysex data.
+ char *buffer = (char *) malloc( nBytes );
+ if ( buffer == NULL ) {
+ errorString_ = "MidiOutWinMM::sendMessage: error allocating sysex message memory!";
+ RtMidi::error( RtError::MEMORY_ERROR, errorString_ );
+ }
+
+ // Copy data to buffer.
+ for ( unsigned int i=0; i<nBytes; ++i ) buffer[i] = message->at(i);
+
+ // Create and prepare MIDIHDR structure.
+ MIDIHDR sysex;
+ sysex.lpData = (LPSTR) buffer;
+ sysex.dwBufferLength = nBytes;
+ sysex.dwFlags = 0;
+ result = midiOutPrepareHeader( data->outHandle, &sysex, sizeof(MIDIHDR) );
+ if ( result != MMSYSERR_NOERROR ) {
+ free( buffer );
+ errorString_ = "MidiOutWinMM::sendMessage: error preparing sysex header.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ // Send the message.
+ result = midiOutLongMsg( data->outHandle, &sysex, sizeof(MIDIHDR) );
+ if ( result != MMSYSERR_NOERROR ) {
+ free( buffer );
+ errorString_ = "MidiOutWinMM::sendMessage: error sending sysex message.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ // Unprepare the buffer and MIDIHDR.
+ while ( MIDIERR_STILLPLAYING == midiOutUnprepareHeader( data->outHandle, &sysex, sizeof (MIDIHDR) ) ) Sleep( 1 );
+ free( buffer );
+
+ }
+ else { // Channel or system message.
+
+ // Make sure the message size isn't too big.
+ if ( nBytes > 3 ) {
+ errorString_ = "MidiOutWinMM::sendMessage: message size is greater than 3 bytes (and not sysex)!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return;
+ }
+
+ // Pack MIDI bytes into double word.
+ DWORD packet;
+ unsigned char *ptr = (unsigned char *) &packet;
+ for ( unsigned int i=0; i<nBytes; ++i ) {
+ *ptr = message->at(i);
+ ++ptr;
+ }
+
+ // Send the message immediately.
+ result = midiOutShortMsg( data->outHandle, packet );
+ if ( result != MMSYSERR_NOERROR ) {
+ errorString_ = "MidiOutWinMM::sendMessage: error sending MIDI message.";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+ }
+}
+
+#endif // __WINDOWS_MM__
+
+// *********************************************************************//
+// API: WINDOWS Kernel Streaming
+//
+// Written by Sebastien Alaiwan, 2012.
+//
+// NOTE BY GARY: much of the KS-specific code below probably should go in a separate file.
+//
+// *********************************************************************//
+
+#if defined(__WINDOWS_KS__)
+
+#include <string>
+#include <vector>
+#include <memory>
+#include <stdexcept>
+#include <sstream>
+#include <windows.h>
+#include <setupapi.h>
+#include <mmsystem.h>
+
+#include "ks.h"
+#include "ksmedia.h"
+
+#define INSTANTIATE_GUID(a) GUID const a = { STATIC_ ## a }
+
+INSTANTIATE_GUID(GUID_NULL);
+INSTANTIATE_GUID(KSPROPSETID_Pin);
+INSTANTIATE_GUID(KSPROPSETID_Connection);
+INSTANTIATE_GUID(KSPROPSETID_Topology);
+INSTANTIATE_GUID(KSINTERFACESETID_Standard);
+INSTANTIATE_GUID(KSMEDIUMSETID_Standard);
+INSTANTIATE_GUID(KSDATAFORMAT_TYPE_MUSIC);
+INSTANTIATE_GUID(KSDATAFORMAT_SUBTYPE_MIDI);
+INSTANTIATE_GUID(KSDATAFORMAT_SPECIFIER_NONE);
+
+#undef INSTANTIATE_GUID
+
+typedef std::basic_string<TCHAR> tstring;
+
+inline bool IsValid(HANDLE handle)
+{
+ return handle != NULL && handle != INVALID_HANDLE_VALUE;
+}
+
+class ComException : public std::runtime_error
+{
+private:
+ static std::string MakeString(std::string const& s, HRESULT hr)
+ {
+ std::stringstream ss;
+ ss << "(error 0x" << std::hex << hr << ")";
+ return s + ss.str();
+ }
+
+public:
+ ComException(std::string const& s, HRESULT hr) :
+ std::runtime_error(MakeString(s, hr))
+ {
+ }
+};
+
+template<typename TFilterType>
+class CKsEnumFilters
+{
+public:
+ ~CKsEnumFilters()
+ {
+ DestroyLists();
+ }
+
+ void EnumFilters(GUID const* categories, size_t numCategories)
+ {
+ DestroyLists();
+
+ if (categories == 0)
+ {
+ printf ("Error: CKsEnumFilters: invalid argument\n");
+ assert(0);
+ }
+ // Get a handle to the device set specified by the guid
+ HDEVINFO hDevInfo = ::SetupDiGetClassDevs(&categories[0], NULL, NULL, DIGCF_PRESENT | DIGCF_DEVICEINTERFACE);
+ if (!IsValid(hDevInfo))
+ {
+ printf ("Error: CKsEnumFilters: no devices found");
+ assert (0);
+ }
+
+ // Loop through members of the set and get details for each
+ for (int iClassMember=0;;iClassMember++) {
+ {
+ SP_DEVICE_INTERFACE_DATA DID;
+ DID.cbSize = sizeof(DID);
+ DID.Reserved = 0;
+
+ bool fRes = ::SetupDiEnumDeviceInterfaces(hDevInfo, NULL, &categories[0], iClassMember, &DID);
+ if (!fRes)
+ break;
+
+ // Get filter friendly name
+ HKEY hRegKey = ::SetupDiOpenDeviceInterfaceRegKey(hDevInfo, &DID, 0, KEY_READ);
+ if (hRegKey == INVALID_HANDLE_VALUE)
+ {
+ assert(0);
+ printf "CKsEnumFilters: interface has no registry\n");
+ }
+ char friendlyName[256];
+ DWORD dwSize = sizeof friendlyName;
+ LONG lval = ::RegQueryValueEx(hRegKey, TEXT("FriendlyName"), NULL, NULL, (LPBYTE)friendlyName, &dwSize);
+ ::RegCloseKey(hRegKey);
+ if (lval != ERROR_SUCCESS)
+ {
+ assert(0);
+ printf ("CKsEnumFilters: interface has no friendly name");
+ }
+ // Get details for the device registered in this class
+ DWORD const cbItfDetails = sizeof(SP_DEVICE_INTERFACE_DETAIL_DATA) + MAX_PATH * sizeof(WCHAR);
+ std::vector<BYTE> buffer(cbItfDetails);
+
+ SP_DEVICE_INTERFACE_DETAIL_DATA* pDevInterfaceDetails = reinterpret_cast<SP_DEVICE_INTERFACE_DETAIL_DATA*>(&buffer[0]);
+ pDevInterfaceDetails->cbSize = sizeof(*pDevInterfaceDetails);
+
+ SP_DEVINFO_DATA DevInfoData;
+ DevInfoData.cbSize = sizeof(DevInfoData);
+ DevInfoData.Reserved = 0;
+
+ fRes = ::SetupDiGetDeviceInterfaceDetail(hDevInfo, &DID, pDevInterfaceDetails, cbItfDetails, NULL, &DevInfoData);
+ if (!fRes)
+ {
+ printf("CKsEnumFilters: could not get interface details");
+ assert(0);
+ }
+ // check additional category guids which may (or may not) have been supplied
+ for (size_t i=1; i < numCategories; ++i) {
+ SP_DEVICE_INTERFACE_DATA DIDAlias;
+ DIDAlias.cbSize = sizeof(DIDAlias);
+ DIDAlias.Reserved = 0;
+
+ fRes = ::SetupDiGetDeviceInterfaceAlias(hDevInfo, &DID, &categories[i], &DIDAlias);
+ if (!fRes)
+ {
+ printf("CKsEnumFilters: could not get interface alias");
+ assert(0);
+ }
+ // Check if the this interface alias is enabled.
+ if (!DIDAlias.Flags || (DIDAlias.Flags & SPINT_REMOVED))
+ {
+ printf("CKsEnumFilters: interface alias is not enabled");
+ assert(0);
+ }
+ }
+
+ std::auto_ptr<TFilterType> pFilter(new TFilterType(pDevInterfaceDetails->DevicePath, friendlyName));
+
+ pFilter->Instantiate();
+ pFilter->FindMidiPins();
+ pFilter->Validate();
+
+ m_Filters.push_back(pFilter.release());
+ }
+ }
+
+ ::SetupDiDestroyDeviceInfoList(hDevInfo);
+ }
+
+private:
+ void DestroyLists()
+ {
+ for (size_t i=0;i < m_Filters.size();++i)
+ delete m_Filters[i];
+ m_Filters.clear();
+ }
+
+public:
+ // TODO: make this private.
+ std::vector<TFilterType*> m_Filters;
+};
+
+class CKsObject
+{
+public:
+ CKsObject(HANDLE handle) : m_handle(handle)
+ {
+ }
+
+protected:
+ HANDLE m_handle;
+
+ void SetProperty(REFGUID guidPropertySet, ULONG nProperty, void* pvValue, ULONG cbValue)
+ {
+ KSPROPERTY ksProperty;
+ memset(&ksProperty, 0, sizeof ksProperty);
+ ksProperty.Set = guidPropertySet;
+ ksProperty.Id = nProperty;
+ ksProperty.Flags = KSPROPERTY_TYPE_SET;
+
+ HRESULT hr = DeviceIoControlKsProperty(ksProperty, pvValue, cbValue);
+ if (FAILED(hr))
+ {
+ printf("CKsObject::SetProperty: could not set property");
+ exit(0);
+ }
+ }
+
+private:
+
+ HRESULT DeviceIoControlKsProperty(KSPROPERTY& ksProperty, void* pvValue, ULONG cbValue)
+ {
+ ULONG ulReturned;
+ return ::DeviceIoControl(
+ m_handle,
+ IOCTL_KS_PROPERTY,
+ &ksProperty,
+ sizeof(ksProperty),
+ pvValue,
+ cbValue,
+ &ulReturned,
+ NULL);
+ }
+};
+
+class CKsPin;
+
+class CKsFilter : public CKsObject
+{
+ friend class CKsPin;
+
+public:
+ CKsFilter(tstring const& name, std::string const& sFriendlyName);
+ virtual ~CKsFilter();
+
+ virtual void Instantiate();
+
+ template<typename T>
+ T GetPinProperty(ULONG nPinId, ULONG nProperty)
+ {
+ ULONG ulReturned = 0;
+ T value;
+
+ KSP_PIN ksPProp;
+ ksPProp.Property.Set = KSPROPSETID_Pin;
+ ksPProp.Property.Id = nProperty;
+ ksPProp.Property.Flags = KSPROPERTY_TYPE_GET;
+ ksPProp.PinId = nPinId;
+ ksPProp.Reserved = 0;
+
+ HRESULT hr = ::DeviceIoControl(
+ m_handle,
+ IOCTL_KS_PROPERTY,
+ &ksPProp,
+ sizeof(KSP_PIN),
+ &value,
+ sizeof(value),
+ &ulReturned,
+ NULL);
+ if (FAILED(hr))
+ {
+ printf("CKsFilter::GetPinProperty: failed to retrieve property");
+ exit(0);
+ }
+
+ return value;
+ }
+
+ void GetPinPropertyMulti(ULONG nPinId, REFGUID guidPropertySet, ULONG nProperty, PKSMULTIPLE_ITEM* ppKsMultipleItem)
+ {
+ HRESULT hr;
+
+ KSP_PIN ksPProp;
+ ksPProp.Property.Set = guidPropertySet;
+ ksPProp.Property.Id = nProperty;
+ ksPProp.Property.Flags = KSPROPERTY_TYPE_GET;
+ ksPProp.PinId = nPinId;
+ ksPProp.Reserved = 0;
+
+ ULONG cbMultipleItem = 0;
+ hr = ::DeviceIoControl(m_handle,
+ IOCTL_KS_PROPERTY,
+ &ksPProp.Property,
+ sizeof(KSP_PIN),
+ NULL,
+ 0,
+ &cbMultipleItem,
+ NULL);
+ if (FAILED(hr))
+ {
+ printf("CKsFilter::GetPinPropertyMulti: cannot get property");
+ exit(0);
+ }
+
+ *ppKsMultipleItem = (PKSMULTIPLE_ITEM) new BYTE[cbMultipleItem];
+
+ ULONG ulReturned = 0;
+ hr = ::DeviceIoControl(
+ m_handle,
+ IOCTL_KS_PROPERTY,
+ &ksPProp,
+ sizeof(KSP_PIN),
+ (PVOID)*ppKsMultipleItem,
+ cbMultipleItem,
+ &ulReturned,
+ NULL);
+ if (FAILED(hr))
+ {
+ printf("CKsFilter::GetPinPropertyMulti: cannot get property");
+ exit(0);
+ }
+ }
+
+ std::string const& GetFriendlyName() const
+ {
+ return m_sFriendlyName;
+ }
+
+protected:
+
+ std::vector<CKsPin*> m_Pins; // this list owns the pins.
+
+ std::vector<CKsPin*> m_RenderPins;
+ std::vector<CKsPin*> m_CapturePins;
+
+private:
+ std::string const m_sFriendlyName; // friendly name eg "Virus TI Synth"
+ tstring const m_sName; // Filter path, eg "\\?\usb#vid_133e&pid_0815...\vtimidi02"
+};
+
+class CKsPin : public CKsObject
+{
+public:
+ CKsPin(CKsFilter* pFilter, ULONG nId);
+ virtual ~CKsPin();
+
+ virtual void Instantiate();
+
+ void ClosePin();
+
+ void SetState(KSSTATE ksState);
+
+ void WriteData(KSSTREAM_HEADER* pKSSTREAM_HEADER, OVERLAPPED* pOVERLAPPED);
+ void ReadData(KSSTREAM_HEADER* pKSSTREAM_HEADER, OVERLAPPED* pOVERLAPPED);
+
+ KSPIN_DATAFLOW GetDataFlow() const
+ {
+ return m_DataFlow;
+ }
+
+ bool IsSink() const
+ {
+ return m_Communication == KSPIN_COMMUNICATION_SINK
+ || m_Communication == KSPIN_COMMUNICATION_BOTH;
+ }
+
+
+protected:
+ PKSPIN_CONNECT m_pKsPinConnect; // creation parameters of pin
+ CKsFilter* const m_pFilter;
+
+ ULONG m_cInterfaces;
+ PKSIDENTIFIER m_pInterfaces;
+ PKSMULTIPLE_ITEM m_pmiInterfaces;
+
+ ULONG m_cMediums;
+ PKSIDENTIFIER m_pMediums;
+ PKSMULTIPLE_ITEM m_pmiMediums;
+
+ ULONG m_cDataRanges;
+ PKSDATARANGE m_pDataRanges;
+ PKSMULTIPLE_ITEM m_pmiDataRanges;
+
+ KSPIN_DATAFLOW m_DataFlow;
+ KSPIN_COMMUNICATION m_Communication;
+};
+
+CKsFilter::CKsFilter(tstring const& sName, std::string const& sFriendlyName) :
+ CKsObject(INVALID_HANDLE_VALUE),
+ m_sFriendlyName(sFriendlyName),
+ m_sName(sName)
+{
+ if (sName.empty())
+ {
+ printf("CKsFilter::CKsFilter: name can't be empty");
+ assert(0);
+ }
+}
+
+CKsFilter::~CKsFilter()
+{
+ for (size_t i=0;i < m_Pins.size();++i)
+ delete m_Pins[i];
+
+ if (IsValid(m_handle))
+ ::CloseHandle(m_handle);
+}
+
+void CKsFilter::Instantiate()
+{
+ m_handle = CreateFile(
+ m_sName.c_str(),
+ GENERIC_READ | GENERIC_WRITE,
+ 0,
+ NULL,
+ OPEN_EXISTING,
+ FILE_ATTRIBUTE_NORMAL | FILE_FLAG_OVERLAPPED,
+ NULL);
+
+ if (!IsValid(m_handle))
+ {
+ DWORD const dwError = GetLastError();
+ throw ComException("CKsFilter::Instantiate: can't open driver", HRESULT_FROM_WIN32(dwError));
+ }
+}
+
+CKsPin::CKsPin(CKsFilter* pFilter, ULONG PinId) :
+ CKsObject(INVALID_HANDLE_VALUE),
+ m_pKsPinConnect(NULL),
+ m_pFilter(pFilter)
+{
+ m_Communication = m_pFilter->GetPinProperty<KSPIN_COMMUNICATION>(PinId, KSPROPERTY_PIN_COMMUNICATION);
+ m_DataFlow = m_pFilter->GetPinProperty<KSPIN_DATAFLOW>(PinId, KSPROPERTY_PIN_DATAFLOW);
+
+ // Interfaces
+ m_pFilter->GetPinPropertyMulti(
+ PinId,
+ KSPROPSETID_Pin,
+ KSPROPERTY_PIN_INTERFACES,
+ &m_pmiInterfaces);
+
+ m_cInterfaces = m_pmiInterfaces->Count;
+ m_pInterfaces = (PKSPIN_INTERFACE)(m_pmiInterfaces + 1);
+
+ // Mediums
+ m_pFilter->GetPinPropertyMulti(
+ PinId,
+ KSPROPSETID_Pin,
+ KSPROPERTY_PIN_MEDIUMS,
+ &m_pmiMediums);
+
+ m_cMediums = m_pmiMediums->Count;
+ m_pMediums = (PKSPIN_MEDIUM)(m_pmiMediums + 1);
+
+ // Data ranges
+ m_pFilter->GetPinPropertyMulti(
+ PinId,
+ KSPROPSETID_Pin,
+ KSPROPERTY_PIN_DATARANGES,
+ &m_pmiDataRanges);
+
+ m_cDataRanges = m_pmiDataRanges->Count;
+ m_pDataRanges = (PKSDATARANGE)(m_pmiDataRanges + 1);
+}
+
+CKsPin::~CKsPin()
+{
+ ClosePin();
+
+ delete[] (BYTE*)m_pKsPinConnect;
+ delete[] (BYTE*)m_pmiDataRanges;
+ delete[] (BYTE*)m_pmiInterfaces;
+ delete[] (BYTE*)m_pmiMediums;
+}
+
+void CKsPin::ClosePin()
+{
+ if (IsValid(m_handle)) {
+ SetState(KSSTATE_STOP);
+ ::CloseHandle(m_handle);
+ }
+ m_handle = INVALID_HANDLE_VALUE;
+}
+
+void CKsPin::SetState(KSSTATE ksState)
+{
+ SetProperty(KSPROPSETID_Connection, KSPROPERTY_CONNECTION_STATE, &ksState, sizeof(ksState));
+}
+
+void CKsPin::Instantiate()
+{
+ if (!m_pKsPinConnect)
+ {
+ printf("CKsPin::Instanciate: abstract pin");
+ assert(0);
+ }
+ DWORD const dwResult = KsCreatePin(m_pFilter->m_handle, m_pKsPinConnect, GENERIC_WRITE | GENERIC_READ, &m_handle);
+ if (dwResult != ERROR_SUCCESS)
+ throw ComException("CKsMidiCapFilter::CreateRenderPin: Pin instanciation failed", HRESULT_FROM_WIN32(dwResult));
+}
+
+void CKsPin::WriteData(KSSTREAM_HEADER* pKSSTREAM_HEADER, OVERLAPPED* pOVERLAPPED)
+{
+ DWORD cbWritten;
+ BOOL fRes = ::DeviceIoControl(
+ m_handle,
+ IOCTL_KS_WRITE_STREAM,
+ NULL,
+ 0,
+ pKSSTREAM_HEADER,
+ pKSSTREAM_HEADER->Size,
+ &cbWritten,
+ pOVERLAPPED);
+ if (!fRes) {
+ DWORD const dwError = GetLastError();
+ if (dwError != ERROR_IO_PENDING)
+ throw ComException("CKsPin::WriteData: DeviceIoControl failed", HRESULT_FROM_WIN32(dwError));
+ }
+}
+
+void CKsPin::ReadData(KSSTREAM_HEADER* pKSSTREAM_HEADER, OVERLAPPED* pOVERLAPPED)
+{
+ DWORD cbReturned;
+ BOOL fRes = ::DeviceIoControl(
+ m_handle,
+ IOCTL_KS_READ_STREAM,
+ NULL,
+ 0,
+ pKSSTREAM_HEADER,
+ pKSSTREAM_HEADER->Size,
+ &cbReturned,
+ pOVERLAPPED);
+ if (!fRes) {
+ DWORD const dwError = GetLastError();
+ if (dwError != ERROR_IO_PENDING)
+ throw ComException("CKsPin::ReadData: DeviceIoControl failed", HRESULT_FROM_WIN32(dwError));
+ }
+}
+
+class CKsMidiFilter : public CKsFilter
+{
+public:
+ void FindMidiPins();
+
+protected:
+ CKsMidiFilter(tstring const& sPath, std::string const& sFriendlyName);
+};
+
+class CKsMidiPin : public CKsPin
+{
+public:
+ CKsMidiPin(CKsFilter* pFilter, ULONG nId);
+};
+
+class CKsMidiRenFilter : public CKsMidiFilter
+{
+public:
+ CKsMidiRenFilter(tstring const& sPath, std::string const& sFriendlyName);
+ CKsMidiPin* CreateRenderPin();
+
+ void Validate()
+ {
+ if (m_RenderPins.empty())
+ {
+ printf("Could not find a MIDI render pin");
+ assert(0);
+ }
+ }
+};
+
+class CKsMidiCapFilter : public CKsMidiFilter
+{
+public:
+ CKsMidiCapFilter(tstring const& sPath, std::string const& sFriendlyName);
+ CKsMidiPin* CreateCapturePin();
+
+ void Validate()
+ {
+ if (m_CapturePins.empty())
+ {
+ assert(0);
+ printf("Could not find a MIDI capture pin");
+ }
+ }
+};
+
+CKsMidiFilter::CKsMidiFilter(tstring const& sPath, std::string const& sFriendlyName) :
+ CKsFilter(sPath, sFriendlyName)
+{
+}
+
+void CKsMidiFilter::FindMidiPins()
+{
+ ULONG numPins = GetPinProperty<ULONG>(0, KSPROPERTY_PIN_CTYPES);
+
+ for (ULONG iPin = 0; iPin < numPins; ++iPin) {
+ {
+ KSPIN_COMMUNICATION com = GetPinProperty<KSPIN_COMMUNICATION>(iPin, KSPROPERTY_PIN_COMMUNICATION);
+ if (com != KSPIN_COMMUNICATION_SINK && com != KSPIN_COMMUNICATION_BOTH)
+ {
+ printf("Unknown pin communication value");
+ assert(0);
+ }
+
+ m_Pins.push_back(new CKsMidiPin(this, iPin));
+ }
+
+ }
+
+ m_RenderPins.clear();
+ m_CapturePins.clear();
+
+ for (size_t i = 0; i < m_Pins.size(); ++i) {
+ CKsPin* const pPin = m_Pins[i];
+
+ if (pPin->IsSink()) {
+ if (pPin->GetDataFlow() == KSPIN_DATAFLOW_IN)
+ m_RenderPins.push_back(pPin);
+ else
+ m_CapturePins.push_back(pPin);
+ }
+ }
+
+ if (m_RenderPins.empty() && m_CapturePins.empty())
+ {
+ printf("No valid pins found on the filter.");
+ assert(0);
+
+ }
+}
+
+CKsMidiRenFilter::CKsMidiRenFilter(tstring const& sPath, std::string const& sFriendlyName) :
+ CKsMidiFilter(sPath, sFriendlyName)
+{
+}
+
+CKsMidiPin* CKsMidiRenFilter::CreateRenderPin()
+{
+ if (m_RenderPins.empty())
+ {
+ printf("Could not find a MIDI render pin");
+ assert(0);
+ }
+
+ CKsMidiPin* pPin = (CKsMidiPin*)m_RenderPins[0];
+ pPin->Instantiate();
+ return pPin;
+}
+
+CKsMidiCapFilter::CKsMidiCapFilter(tstring const& sPath, std::string const& sFriendlyName) :
+ CKsMidiFilter(sPath, sFriendlyName)
+{
+}
+
+CKsMidiPin* CKsMidiCapFilter::CreateCapturePin()
+{
+ if (m_CapturePins.empty())
+ {
+ printf("Could not find a MIDI capture pin");
+ assert(0);
+ }
+ CKsMidiPin* pPin = (CKsMidiPin*)m_CapturePins[0];
+ pPin->Instantiate();
+ return pPin;
+}
+
+CKsMidiPin::CKsMidiPin(CKsFilter* pFilter, ULONG nId) :
+ CKsPin(pFilter, nId)
+{
+ DWORD const cbPinCreateSize = sizeof(KSPIN_CONNECT) + sizeof(KSDATAFORMAT);
+ m_pKsPinConnect = (PKSPIN_CONNECT) new BYTE[cbPinCreateSize];
+
+ m_pKsPinConnect->Interface.Set = KSINTERFACESETID_Standard;
+ m_pKsPinConnect->Interface.Id = KSINTERFACE_STANDARD_STREAMING;
+ m_pKsPinConnect->Interface.Flags = 0;
+ m_pKsPinConnect->Medium.Set = KSMEDIUMSETID_Standard;
+ m_pKsPinConnect->Medium.Id = KSMEDIUM_TYPE_ANYINSTANCE;
+ m_pKsPinConnect->Medium.Flags = 0;
+ m_pKsPinConnect->PinId = nId;
+ m_pKsPinConnect->PinToHandle = NULL;
+ m_pKsPinConnect->Priority.PriorityClass = KSPRIORITY_NORMAL;
+ m_pKsPinConnect->Priority.PrioritySubClass = 1;
+
+ // point m_pDataFormat to just after the pConnect struct
+ KSDATAFORMAT* m_pDataFormat = (KSDATAFORMAT*)(m_pKsPinConnect + 1);
+ m_pDataFormat->FormatSize = sizeof(KSDATAFORMAT);
+ m_pDataFormat->Flags = 0;
+ m_pDataFormat->SampleSize = 0;
+ m_pDataFormat->Reserved = 0;
+ m_pDataFormat->MajorFormat = GUID(KSDATAFORMAT_TYPE_MUSIC);
+ m_pDataFormat->SubFormat = GUID(KSDATAFORMAT_SUBTYPE_MIDI);
+ m_pDataFormat->Specifier = GUID(KSDATAFORMAT_SPECIFIER_NONE);
+
+ bool hasStdStreamingInterface = false;
+ bool hasStdStreamingMedium = false;
+
+ for ( ULONG i = 0; i < m_cInterfaces; i++ ) {
+ if (m_pInterfaces[i].Set == KSINTERFACESETID_Standard
+ && m_pInterfaces[i].Id == KSINTERFACE_STANDARD_STREAMING)
+ hasStdStreamingInterface = true;
+ }
+
+ for (ULONG i = 0; i < m_cMediums; i++) {
+ if (m_pMediums[i].Set == KSMEDIUMSETID_Standard
+ && m_pMediums[i].Id == KSMEDIUM_STANDARD_DEVIO)
+ hasStdStreamingMedium = true;
+ }
+
+ if (!hasStdStreamingInterface) // No standard streaming interfaces on the pin
+ {
+ printf("CKsMidiPin::CKsMidiPin: no standard streaming interface");
+ assert(0);
+ }
+
+ if (!hasStdStreamingMedium) // No standard streaming mediums on the pin
+ {
+ printf("CKsMidiPin::CKsMidiPin: no standard streaming medium")
+ assert(0);
+ };
+
+ bool hasMidiDataRange = false;
+
+ BYTE const* pDataRangePtr = reinterpret_cast<BYTE const*>(m_pDataRanges);
+
+ for (ULONG i = 0; i < m_cDataRanges; ++i) {
+ KSDATARANGE const* pDataRange = reinterpret_cast<KSDATARANGE const*>(pDataRangePtr);
+
+ if (pDataRange->SubFormat == KSDATAFORMAT_SUBTYPE_MIDI) {
+ hasMidiDataRange = true;
+ break;
+ }
+
+ pDataRangePtr += pDataRange->FormatSize;
+ }
+
+ if (!hasMidiDataRange) // No MIDI dataranges on the pin
+ {
+ printf("CKsMidiPin::CKsMidiPin: no MIDI datarange");
+ assert(0);
+ }
+}
+
+
+struct WindowsKsData
+{
+ WindowsKsData() : m_pPin(NULL), m_Buffer(1024), m_hInputThread(NULL)
+ {
+ memset(&overlapped, 0, sizeof(OVERLAPPED));
+ m_hExitEvent = ::CreateEvent(NULL, FALSE, FALSE, NULL);
+ overlapped.hEvent = ::CreateEvent(NULL, FALSE, FALSE, NULL);
+ m_hInputThread = NULL;
+ }
+
+ ~WindowsKsData()
+ {
+ ::CloseHandle(overlapped.hEvent);
+ ::CloseHandle(m_hExitEvent);
+ }
+
+ OVERLAPPED overlapped;
+ CKsPin* m_pPin;
+ std::vector<unsigned char> m_Buffer;
+ std::auto_ptr<CKsEnumFilters<CKsMidiCapFilter> > m_pCaptureEnum;
+ std::auto_ptr<CKsEnumFilters<CKsMidiRenFilter> > m_pRenderEnum;
+ HANDLE m_hInputThread;
+ HANDLE m_hExitEvent;
+};
+
+// *********************************************************************//
+// API: WINDOWS Kernel Streaming
+// Class Definitions: MidiInWinKS
+// *********************************************************************//
+
+DWORD WINAPI midiKsInputThread(VOID* pUser)
+{
+ MidiInApi::RtMidiInData* data = static_cast<MidiInApi::RtMidiInData*>(pUser);
+ WindowsKsData* apiData = static_cast<WindowsKsData*>(data->apiData);
+
+ HANDLE hEvents[] = { apiData->overlapped.hEvent, apiData->m_hExitEvent };
+
+ while ( true ) {
+ KSSTREAM_HEADER packet;
+ memset(&packet, 0, sizeof packet);
+ packet.Size = sizeof(KSSTREAM_HEADER);
+ packet.PresentationTime.Time = 0;
+ packet.PresentationTime.Numerator = 1;
+ packet.PresentationTime.Denominator = 1;
+ packet.Data = &apiData->m_Buffer[0];
+ packet.DataUsed = 0;
+ packet.FrameExtent = apiData->m_Buffer.size();
+ apiData->m_pPin->ReadData(&packet, &apiData->overlapped);
+
+ DWORD dwRet = ::WaitForMultipleObjects(2, hEvents, FALSE, INFINITE);
+
+ if ( dwRet == WAIT_OBJECT_0 ) {
+ // parse packet
+ unsigned char* pData = (unsigned char*)packet.Data;
+ unsigned int iOffset = 0;
+
+ while ( iOffset < packet.DataUsed ) {
+ KSMUSICFORMAT* pMusic = (KSMUSICFORMAT*)&pData[iOffset];
+ iOffset += sizeof(KSMUSICFORMAT);
+
+ MidiInApi::MidiMessage message;
+ message.timeStamp = 0;
+ for(size_t i=0;i < pMusic->ByteCount;++i)
+ message.bytes.push_back(pData[iOffset+i]);
+
+ if ( data->usingCallback ) {
+ RtMidiIn::RtMidiCallback callback = (RtMidiIn::RtMidiCallback)data->userCallback;
+ callback(message.timeStamp, &message.bytes, data->userData);
+ }
+ else {
+ // As long as we haven't reached our queue size limit, push the message.
+ if ( data->queue.size < data->queue.ringSize ) {
+ data->queue.ring[data->queue.back++] = message;
+ if(data->queue.back == data->queue.ringSize)
+ data->queue.back = 0;
+ data->queue.size++;
+ }
+ else
+ std::cerr << "\nRtMidiIn: message queue limit reached!!\n\n";
+ }
+
+ iOffset += pMusic->ByteCount;
+
+ // re-align on 32 bits
+ if ( iOffset % 4 != 0 )
+ iOffset += (4 - iOffset % 4);
+ }
+ }
+ else
+ break;
+ }
+ return 0;
+}
+
+MidiInWinKS :: MidiInWinKS( const std::string clientName, unsigned int queueSizeLimit ) : MidiInApi( queueSizeLimit )
+{
+ initialize( clientName );
+}
+
+void MidiInWinKS :: initialize( const std::string& clientName )
+{
+ WindowsKsData* data = new WindowsKsData;
+ apiData_ = (void*)data;
+ inputData_.apiData = data;
+
+ GUID const aguidEnumCats[] =
+ {
+ { STATIC_KSCATEGORY_AUDIO }, { STATIC_KSCATEGORY_CAPTURE }
+ };
+ data->m_pCaptureEnum.reset(new CKsEnumFilters<CKsMidiCapFilter> );
+ data->m_pCaptureEnum->EnumFilters(aguidEnumCats, 2);
+}
+
+MidiInWinKS :: ~MidiInWinKS()
+{
+ WindowsKsData* data = static_cast<WindowsKsData*>(apiData_);
+ {
+ if ( data->m_pPin )
+ closePort();
+ }
+
+ delete data;
+}
+
+void MidiInWinKS :: openPort( unsigned int portNumber, const std::string portName )
+{
+ WindowsKsData* data = static_cast<WindowsKsData*>(apiData_);
+
+ if ( portNumber < 0 || portNumber >= data->m_pCaptureEnum->m_Filters.size() ) {
+ std::stringstream ost;
+ ost << "MidiInWinKS::openPort: the 'portNumber' argument (" << portNumber << ") is invalid.";
+ errorString_ = ost.str();
+ RtMidi::error( RtError::WARNING, errorString_ );
+ }
+
+ CKsMidiCapFilter* pFilter = data->m_pCaptureEnum->m_Filters[portNumber];
+ data->m_pPin = pFilter->CreateCapturePin();
+
+ if ( data->m_pPin == NULL ) {
+ std::stringstream ost;
+ ost << "MidiInWinKS::openPort: KS error opening port (could not create pin)";
+ errorString_ = ost.str();
+ RtMidi::error( RtError::WARNING, errorString_ );
+ }
+
+ data->m_pPin->SetState(KSSTATE_RUN);
+
+ DWORD threadId;
+ data->m_hInputThread = ::CreateThread(NULL, 0, &midiKsInputThread, &inputData_, 0, &threadId);
+ if ( data->m_hInputThread == NULL ) {
+ std::stringstream ost;
+ ost << "MidiInWinKS::initialize: Could not create input thread : Windows error " << GetLastError() << std::endl;;
+ errorString_ = ost.str();
+ RtMidi::error( RtError::WARNING, errorString_ );
+ }
+
+ connected_ = true;
+}
+
+void MidiInWinKS :: openVirtualPort( const std::string portName )
+{
+ // This function cannot be implemented for the Windows KS MIDI API.
+ errorString_ = "MidiInWinKS::openVirtualPort: cannot be implemented in Windows KS MIDI API!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+}
+
+unsigned int MidiInWinKS :: getPortCount()
+{
+ WindowsKsData* data = static_cast<WindowsKsData*>(apiData_);
+ return (unsigned int)data->m_pCaptureEnum->m_Filters.size();
+}
+
+std::string MidiInWinKS :: getPortName(unsigned int portNumber)
+{
+ WindowsKsData* data = static_cast<WindowsKsData*>(apiData_);
+
+ if(portNumber < 0 || portNumber >= data->m_pCaptureEnum->m_Filters.size()) {
+ std::stringstream ost;
+ ost << "MidiInWinKS::getPortName: the 'portNumber' argument (" << portNumber << ") is invalid.";
+ errorString_ = ost.str();
+ RtMidi::error( RtError::WARNING, errorString_ );
+ }
+
+ CKsMidiCapFilter* pFilter = data->m_pCaptureEnum->m_Filters[portNumber];
+ return pFilter->GetFriendlyName();
+}
+
+void MidiInWinKS :: closePort()
+{
+ WindowsKsData* data = static_cast<WindowsKsData*>(apiData_);
+ connected_ = false;
+
+ if(data->m_hInputThread) {
+ ::SignalObjectAndWait(data->m_hExitEvent, data->m_hInputThread, INFINITE, FALSE);
+ ::CloseHandle(data->m_hInputThread);
+ }
+
+ if(data->m_pPin) {
+ data->m_pPin->SetState(KSSTATE_PAUSE);
+ data->m_pPin->SetState(KSSTATE_STOP);
+ data->m_pPin->ClosePin();
+ data->m_pPin = NULL;
+ }
+}
+
+// *********************************************************************//
+// API: WINDOWS Kernel Streaming
+// Class Definitions: MidiOutWinKS
+// *********************************************************************//
+
+MidiOutWinKS :: MidiOutWinKS( const std::string clientName ) : MidiOutApi()
+{
+ initialize( clientName );
+}
+
+void MidiOutWinKS :: initialize( const std::string& clientName )
+{
+ WindowsKsData* data = new WindowsKsData;
+
+ data->m_pPin = NULL;
+ data->m_pRenderEnum.reset(new CKsEnumFilters<CKsMidiRenFilter> );
+ GUID const aguidEnumCats[] =
+ {
+ { STATIC_KSCATEGORY_AUDIO }, { STATIC_KSCATEGORY_RENDER }
+ };
+ data->m_pRenderEnum->EnumFilters(aguidEnumCats, 2);
+
+ apiData_ = (void*)data;
+}
+
+MidiOutWinKS :: ~MidiOutWinKS()
+{
+ // Close a connection if it exists.
+ closePort();
+
+ // Cleanup.
+ WindowsKsData* data = static_cast<WindowsKsData*>(apiData_);
+ delete data;
+}
+
+void MidiOutWinKS :: openPort( unsigned int portNumber, const std::string portName )
+{
+ WindowsKsData* data = static_cast<WindowsKsData*>(apiData_);
+
+ if(portNumber < 0 || portNumber >= data->m_pRenderEnum->m_Filters.size()) {
+ std::stringstream ost;
+ ost << "MidiOutWinKS::openPort: the 'portNumber' argument (" << portNumber << ") is invalid.";
+ errorString_ = ost.str();
+ RtMidi::error( RtError::WARNING, errorString_ );
+ }
+
+ CKsMidiRenFilter* pFilter = data->m_pRenderEnum->m_Filters[portNumber];
+ data->m_pPin = pFilter->CreateRenderPin();
+
+ if(data->m_pPin == NULL) {
+ std::stringstream ost;
+ ost << "MidiOutWinKS::openPort: KS error opening port (could not create pin)";
+ errorString_ = ost.str();
+ RtMidi::error( RtError::WARNING, errorString_ );
+ }
+
+ data->m_pPin->SetState(KSSTATE_RUN);
+ connected_ = true;
+}
+
+void MidiOutWinKS :: openVirtualPort( const std::string portName )
+{
+ // This function cannot be implemented for the Windows KS MIDI API.
+ errorString_ = "MidiOutWinKS::openVirtualPort: cannot be implemented in Windows KS MIDI API!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+}
+
+unsigned int MidiOutWinKS :: getPortCount()
+{
+ WindowsKsData* data = static_cast<WindowsKsData*>(apiData_);
+
+ return (unsigned int)data->m_pRenderEnum->m_Filters.size();
+}
+
+std::string MidiOutWinKS :: getPortName( unsigned int portNumber )
+{
+ WindowsKsData* data = static_cast<WindowsKsData*>(apiData_);
+
+ if ( portNumber < 0 || portNumber >= data->m_pRenderEnum->m_Filters.size() ) {
+ std::stringstream ost;
+ ost << "MidiOutWinKS::getPortName: the 'portNumber' argument (" << portNumber << ") is invalid.";
+ errorString_ = ost.str();
+ RtMidi::error( RtError::WARNING, errorString_ );
+ }
+
+ CKsMidiRenFilter* pFilter = data->m_pRenderEnum->m_Filters[portNumber];
+ return pFilter->GetFriendlyName();
+}
+
+void MidiOutWinKS :: closePort()
+{
+ WindowsKsData* data = static_cast<WindowsKsData*>(apiData_);
+ connected_ = false;
+
+ if ( data->m_pPin ) {
+ data->m_pPin->SetState(KSSTATE_PAUSE);
+ data->m_pPin->SetState(KSSTATE_STOP);
+ data->m_pPin->ClosePin();
+ data->m_pPin = NULL;
+ }
+}
+
+void MidiOutWinKS :: sendMessage(std::vector<unsigned char>* pMessage)
+{
+ std::vector<unsigned char> const& msg = *pMessage;
+ WindowsKsData* data = static_cast<WindowsKsData*>(apiData_);
+ size_t iNumMidiBytes = msg.size();
+ size_t pos = 0;
+
+ // write header
+ KSMUSICFORMAT* pKsMusicFormat = reinterpret_cast<KSMUSICFORMAT*>(&data->m_Buffer[pos]);
+ pKsMusicFormat->TimeDeltaMs = 0;
+ pKsMusicFormat->ByteCount = iNumMidiBytes;
+ pos += sizeof(KSMUSICFORMAT);
+
+ // write MIDI bytes
+ if ( pos + iNumMidiBytes > data->m_Buffer.size() ) {
+ std::stringstream ost;
+ ost << "KsMidiInput::Write: MIDI buffer too small. Required " << pos + iNumMidiBytes << " bytes, only has " << data->m_Buffer.size();
+ errorString_ = ost.str();
+ RtMidi::error( RtError::WARNING, errorString_ );
+ }
+
+ if ( data->m_pPin == NULL ) {
+ std::stringstream ost;
+ ost << "MidiOutWinKS::sendMessage: port is not open";
+ errorString_ = ost.str();
+ RtMidi::error( RtError::WARNING, errorString_ );
+ }
+
+ memcpy(&data->m_Buffer[pos], &msg[0], iNumMidiBytes);
+ pos += iNumMidiBytes;
+
+ KSSTREAM_HEADER packet;
+ memset(&packet, 0, sizeof packet);
+ packet.Size = sizeof(packet);
+ packet.PresentationTime.Time = 0;
+ packet.PresentationTime.Numerator = 1;
+ packet.PresentationTime.Denominator = 1;
+ packet.Data = const_cast<unsigned char*>(&data->m_Buffer[0]);
+ packet.DataUsed = ((pos+3)/4)*4;
+ packet.FrameExtent = data->m_Buffer.size();
+
+ data->m_pPin->WriteData(&packet, NULL);
+}
+
+#endif // __WINDOWS_KS__
+
+//*********************************************************************//
+// API: UNIX JACK
+//
+// Written primarily by Alexander Svetalkin, with updates for delta
+// time by Gary Scavone, April 2011.
+//
+// *********************************************************************//
+
+#if defined(__UNIX_JACK__)
+
+// JACK header files
+#include <jack/jack.h>
+#include <jack/midiport.h>
+#include <jack/ringbuffer.h>
+
+#define JACK_RINGBUFFER_SIZE 16384 // Default size for ringbuffer
+
+struct JackMidiData {
+ jack_client_t *client;
+ jack_port_t *port;
+ jack_ringbuffer_t *buffSize;
+ jack_ringbuffer_t *buffMessage;
+ jack_time_t lastTime;
+ MidiInApi :: RtMidiInData *rtMidiIn;
+ };
+
+//*********************************************************************//
+// API: JACK
+// Class Definitions: MidiInJack
+//*********************************************************************//
+
+int jackProcessIn( jack_nframes_t nframes, void *arg )
+{
+ JackMidiData *jData = (JackMidiData *) arg;
+ MidiInApi :: RtMidiInData *rtData = jData->rtMidiIn;
+ jack_midi_event_t event;
+ jack_time_t long long time;
+
+ // Is port created?
+ if ( jData->port == NULL ) return 0;
+ void *buff = jack_port_get_buffer( jData->port, nframes );
+
+ // We have midi events in buffer
+ int evCount = jack_midi_get_event_count( buff );
+ if ( evCount > 0 ) {
+ MidiInApi::MidiMessage message;
+ message.bytes.clear();
+
+ jack_midi_event_get( &event, buff, 0 );
+
+ for (unsigned int i = 0; i < event.size; i++ )
+ message.bytes.push_back( event.buffer[i] );
+
+ // Compute the delta time.
+ time = jack_get_time();
+ if ( rtData->firstMessage == true )
+ rtData->firstMessage = false;
+ else
+ message.timeStamp = ( time - jData->lastTime ) * 0.000001;
+
+ jData->lastTime = time;
+
+ if ( !rtData->continueSysex ) {
+ if ( rtData->usingCallback ) {
+ RtMidiIn::RtMidiCallback callback = (RtMidiIn::RtMidiCallback) rtData->userCallback;
+ callback( message.timeStamp, &message.bytes, rtData->userData );
+ }
+ else {
+ // As long as we haven't reached our queue size limit, push the message.
+ if ( rtData->queue.size < rtData->queue.ringSize ) {
+ rtData->queue.ring[rtData->queue.back++] = message;
+ if ( rtData->queue.back == rtData->queue.ringSize )
+ rtData->queue.back = 0;
+ rtData->queue.size++;
+ }
+ else
+ std::cerr << "\nMidiInJack: message queue limit reached!!\n\n";
+ }
+ }
+ }
+
+ return 0;
+}
+
+MidiInJack :: MidiInJack( const std::string clientName, unsigned int queueSizeLimit ) : MidiInApi( queueSizeLimit )
+{
+ initialize( clientName );
+}
+
+void MidiInJack :: initialize( const std::string& clientName )
+{
+ JackMidiData *data = new JackMidiData;
+ apiData_ = (void *) data;
+
+ // Initialize JACK client
+ if (( data->client = jack_client_open( clientName.c_str(), JackNullOption, NULL )) == 0) {
+ errorString_ = "MidiInJack::initialize: JACK server not running?";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ return;
+ }
+
+ data->rtMidiIn = &inputData_;
+ data->port = NULL;
+
+ jack_set_process_callback( data->client, jackProcessIn, data );
+ jack_activate( data->client );
+}
+
+MidiInJack :: ~MidiInJack()
+{
+ JackMidiData *data = static_cast<JackMidiData *> (apiData_);
+ closePort();
+
+ jack_client_close( data->client );
+}
+
+void MidiInJack :: openPort( unsigned int portNumber, const std::string portName )
+{
+ JackMidiData *data = static_cast<JackMidiData *> (apiData_);
+
+ // Creating new port
+ if ( data->port == NULL)
+ data->port = jack_port_register( data->client, portName.c_str(),
+ JACK_DEFAULT_MIDI_TYPE, JackPortIsInput, 0 );
+
+ if ( data->port == NULL) {
+ errorString_ = "MidiInJack::openVirtualPort: JACK error creating virtual port";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ // Connecting to the output
+ std::string name = getPortName( portNumber );
+ jack_connect( data->client, name.c_str(), jack_port_name( data->port ) );
+}
+
+void MidiInJack :: openVirtualPort( const std::string portName )
+{
+ JackMidiData *data = static_cast<JackMidiData *> (apiData_);
+
+ if ( data->port == NULL )
+ data->port = jack_port_register( data->client, portName.c_str(),
+ JACK_DEFAULT_MIDI_TYPE, JackPortIsInput, 0 );
+
+ if ( data->port == NULL ) {
+ errorString_ = "MidiInJack::openVirtualPort: JACK error creating virtual port";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+}
+
+unsigned int MidiInJack :: getPortCount()
+{
+ int count = 0;
+ JackMidiData *data = static_cast<JackMidiData *> (apiData_);
+
+ // List of available ports
+ const char **ports = jack_get_ports( data->client, NULL, JACK_DEFAULT_MIDI_TYPE, JackPortIsOutput );
+
+ if ( ports == NULL ) return 0;
+ while ( ports[count] != NULL )
+ count++;
+
+ free( ports );
+
+ return count;
+}
+
+std::string MidiInJack :: getPortName( unsigned int portNumber )
+{
+ JackMidiData *data = static_cast<JackMidiData *> (apiData_);
+ std::ostringstream ost;
+ std::string retStr("");
+
+ // List of available ports
+ const char **ports = jack_get_ports( data->client, NULL,
+ JACK_DEFAULT_MIDI_TYPE, JackPortIsOutput );
+
+ // Check port validity
+ if ( ports == NULL ) {
+ errorString_ = "MidiInJack::getPortName: no ports available!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return retStr;
+ }
+
+ if ( ports[portNumber] == NULL ) {
+ ost << "MidiInJack::getPortName: the 'portNumber' argument (" << portNumber << ") is invalid.";
+ errorString_ = ost.str();
+ RtMidi::error( RtError::WARNING, errorString_ );
+ }
+ else retStr.assign( ports[portNumber] );
+
+ free( ports );
+
+ return retStr;
+}
+
+void MidiInJack :: closePort()
+{
+ JackMidiData *data = static_cast<JackMidiData *> (apiData_);
+
+ if ( data->port == NULL ) return;
+ jack_port_unregister( data->client, data->port );
+ data->port = NULL;
+}
+
+//*********************************************************************//
+// API: JACK
+// Class Definitions: MidiOutJack
+//*********************************************************************//
+
+// Jack process callback
+int jackProcessOut( jack_nframes_t nframes, void *arg )
+{
+ JackMidiData *data = (JackMidiData *) arg;
+ jack_midi_data_t *midiData;
+ int space;
+
+ // Is port created?
+ if ( data->port == NULL ) return 0;
+
+ void *buff = jack_port_get_buffer( data->port, nframes );
+ jack_midi_clear_buffer( buff );
+
+ while ( jack_ringbuffer_read_space( data->buffSize ) > 0 ) {
+ jack_ringbuffer_read( data->buffSize, (char *) &space, (size_t) sizeof(space) );
+ midiData = jack_midi_event_reserve( buff, 0, space );
+
+ jack_ringbuffer_read( data->buffMessage, (char *) midiData, (size_t) space );
+ }
+
+ return 0;
+}
+
+MidiOutJack :: MidiOutJack( const std::string clientName ) : MidiOutApi()
+{
+ initialize( clientName );
+}
+
+void MidiOutJack :: initialize( const std::string& clientName )
+{
+ JackMidiData *data = new JackMidiData;
+
+ data->port = NULL;
+
+ // Initialize JACK client
+ if (( data->client = jack_client_open( clientName.c_str(), JackNullOption, NULL )) == 0) {
+ errorString_ = "MidiOutJack::initialize: JACK server not running?";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ return;
+ }
+
+ jack_set_process_callback( data->client, jackProcessOut, data );
+ data->buffSize = jack_ringbuffer_create( JACK_RINGBUFFER_SIZE );
+ data->buffMessage = jack_ringbuffer_create( JACK_RINGBUFFER_SIZE );
+ jack_activate( data->client );
+
+ apiData_ = (void *) data;
+}
+
+MidiOutJack :: ~MidiOutJack()
+{
+ JackMidiData *data = static_cast<JackMidiData *> (apiData_);
+ closePort();
+
+ // Cleanup
+ jack_client_close( data->client );
+ jack_ringbuffer_free( data->buffSize );
+ jack_ringbuffer_free( data->buffMessage );
+
+ delete data;
+}
+
+void MidiOutJack :: openPort( unsigned int portNumber, const std::string portName )
+{
+ JackMidiData *data = static_cast<JackMidiData *> (apiData_);
+
+ // Creating new port
+ if ( data->port == NULL )
+ data->port = jack_port_register( data->client, portName.c_str(),
+ JACK_DEFAULT_MIDI_TYPE, JackPortIsOutput, 0 );
+
+ if ( data->port == NULL ) {
+ errorString_ = "MidiOutJack::openVirtualPort: JACK error creating virtual port";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+
+ // Connecting to the output
+ std::string name = getPortName( portNumber );
+ jack_connect( data->client, jack_port_name( data->port ), name.c_str() );
+}
+
+void MidiOutJack :: openVirtualPort( const std::string portName )
+{
+ JackMidiData *data = static_cast<JackMidiData *> (apiData_);
+
+ if ( data->port == NULL )
+ data->port = jack_port_register( data->client, portName.c_str(),
+ JACK_DEFAULT_MIDI_TYPE, JackPortIsOutput, 0 );
+
+ if ( data->port == NULL ) {
+ errorString_ = "MidiOutJack::openVirtualPort: JACK error creating virtual port";
+ RtMidi::error( RtError::DRIVER_ERROR, errorString_ );
+ }
+}
+
+unsigned int MidiOutJack :: getPortCount()
+{
+ int count = 0;
+ JackMidiData *data = static_cast<JackMidiData *> (apiData_);
+
+ // List of available ports
+ const char **ports = jack_get_ports( data->client, NULL,
+ JACK_DEFAULT_MIDI_TYPE, JackPortIsInput );
+
+ if ( ports == NULL ) return 0;
+ while ( ports[count] != NULL )
+ count++;
+
+ free( ports );
+
+ return count;
+}
+
+std::string MidiOutJack :: getPortName( unsigned int portNumber )
+{
+ JackMidiData *data = static_cast<JackMidiData *> (apiData_);
+ std::ostringstream ost;
+ std::string retStr("");
+
+ // List of available ports
+ const char **ports = jack_get_ports( data->client, NULL,
+ JACK_DEFAULT_MIDI_TYPE, JackPortIsInput );
+
+ // Check port validity
+ if ( ports == NULL) {
+ errorString_ = "MidiOutJack::getPortName: no ports available!";
+ RtMidi::error( RtError::WARNING, errorString_ );
+ return retStr;
+ }
+
+ if ( ports[portNumber] == NULL) {
+ ost << "MidiOutJack::getPortName: the 'portNumber' argument (" << portNumber << ") is invalid.";
+ errorString_ = ost.str();
+ RtMidi::error( RtError::WARNING, errorString_ );
+ }
+ else retStr.assign( ports[portNumber] );
+
+ free( ports );
+
+ return retStr;
+}
+
+void MidiOutJack :: closePort()
+{
+ JackMidiData *data = static_cast<JackMidiData *> (apiData_);
+
+ if ( data->port == NULL ) return;
+ jack_port_unregister( data->client, data->port );
+ data->port = NULL;
+}
+
+void MidiOutJack :: sendMessage( std::vector<unsigned char> *message )
+{
+ int nBytes = message->size();
+ JackMidiData *data = static_cast<JackMidiData *> (apiData_);
+
+ // Write full message to buffer
+ jack_ringbuffer_write( data->buffMessage, ( const char * ) &( *message )[0],
+ message->size() );
+ jack_ringbuffer_write( data->buffSize, ( char * ) &nBytes, sizeof( nBytes ) );
+}
+
+#endif // __UNIX_JACK__ \ No newline at end of file
diff --git a/examples/ThirdPartyLibs/midi/RtMidi.h b/examples/ThirdPartyLibs/midi/RtMidi.h
new file mode 100644
index 000000000..66eb4fc3c
--- /dev/null
+++ b/examples/ThirdPartyLibs/midi/RtMidi.h
@@ -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 \ No newline at end of file
diff --git a/examples/ThirdPartyLibs/midi/cmidiin.cpp b/examples/ThirdPartyLibs/midi/cmidiin.cpp
new file mode 100644
index 000000000..75d2958b0
--- /dev/null
+++ b/examples/ThirdPartyLibs/midi/cmidiin.cpp
@@ -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;
+} \ No newline at end of file
diff --git a/examples/ThirdPartyLibs/midi/premake4.lua b/examples/ThirdPartyLibs/midi/premake4.lua
new file mode 100644
index 000000000..f71f8dba9
--- /dev/null
+++ b/examples/ThirdPartyLibs/midi/premake4.lua
@@ -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 \ No newline at end of file
diff --git a/examples/ThirdPartyLibs/openvr/bin/linux32/libopenvr_api.so b/examples/ThirdPartyLibs/openvr/bin/linux32/libopenvr_api.so
deleted file mode 100644
index a25054508..000000000
--- a/examples/ThirdPartyLibs/openvr/bin/linux32/libopenvr_api.so
+++ /dev/null
Binary files differ
diff --git a/examples/ThirdPartyLibs/openvr/bin/linux64/libopenvr_api.so b/examples/ThirdPartyLibs/openvr/bin/linux64/libopenvr_api.so
index c3c6d47ca..692a87c0d 100644
--- a/examples/ThirdPartyLibs/openvr/bin/linux64/libopenvr_api.so
+++ b/examples/ThirdPartyLibs/openvr/bin/linux64/libopenvr_api.so
Binary files differ
diff --git a/examples/ThirdPartyLibs/openvr/bin/osx32/libopenvr_api.dylib b/examples/ThirdPartyLibs/openvr/bin/osx32/libopenvr_api.dylib
index b296e20b8..e3e871a41 100644
--- a/examples/ThirdPartyLibs/openvr/bin/osx32/libopenvr_api.dylib
+++ b/examples/ThirdPartyLibs/openvr/bin/osx32/libopenvr_api.dylib
Binary files differ
diff --git a/examples/ThirdPartyLibs/openvr/bin/win32/openvr_api.dll b/examples/ThirdPartyLibs/openvr/bin/win32/openvr_api.dll
index d2b37d56b..2dd3fbee4 100644
--- a/examples/ThirdPartyLibs/openvr/bin/win32/openvr_api.dll
+++ b/examples/ThirdPartyLibs/openvr/bin/win32/openvr_api.dll
Binary files differ
diff --git a/examples/ThirdPartyLibs/openvr/bin/win64/openvr_api.dll b/examples/ThirdPartyLibs/openvr/bin/win64/openvr_api.dll
index d13791a39..9ae492261 100644
--- a/examples/ThirdPartyLibs/openvr/bin/win64/openvr_api.dll
+++ b/examples/ThirdPartyLibs/openvr/bin/win64/openvr_api.dll
Binary files differ
diff --git a/examples/ThirdPartyLibs/openvr/headers/openvr.h b/examples/ThirdPartyLibs/openvr/headers/openvr.h
index df727a3b5..b72fcae97 100644
--- a/examples/ThirdPartyLibs/openvr/headers/openvr.h
+++ b/examples/ThirdPartyLibs/openvr/headers/openvr.h
@@ -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
@@ -1647,6 +1769,21 @@ namespace vr
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;
}
diff --git a/examples/ThirdPartyLibs/openvr/headers/openvr_api.cs b/examples/ThirdPartyLibs/openvr/headers/openvr_api.cs
index a4d71f826..8fcac88dd 100644
--- a/examples/ThirdPartyLibs/openvr/headers/openvr_api.cs
+++ b/examples/ThirdPartyLibs/openvr/headers/openvr_api.cs
@@ -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;
@@ -346,6 +366,11 @@ public struct IVRApplications
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)]
internal _LaunchDashboardOverlay LaunchDashboardOverlay;
@@ -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;
@@ -396,6 +421,31 @@ public struct IVRApplications
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)]
internal _GetStartingApplication GetStartingApplication;
@@ -731,16 +781,6 @@ public struct IVRCompositor
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)]
internal _GetMirrorTextureD3D11 GetMirrorTextureD3D11;
@@ -856,6 +896,26 @@ public struct IVROverlay
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)]
internal _SetOverlayWidthInMeters SetOverlayWidthInMeters;
@@ -1236,44 +1296,44 @@ public struct IVRSettings
internal _Sync Sync;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
- internal delegate bool _GetBool(string pchSection, string pchSettingsKey, bool bDefaultValue, ref EVRSettingsError peError);
+ internal delegate void _SetBool(string pchSection, string pchSettingsKey, bool bValue, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
- internal _GetBool GetBool;
+ internal _SetBool SetBool;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
- internal delegate void _SetBool(string pchSection, string pchSettingsKey, bool bValue, ref EVRSettingsError peError);
+ internal delegate void _SetInt32(string pchSection, string pchSettingsKey, int nValue, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
- internal _SetBool SetBool;
+ internal _SetInt32 SetInt32;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
- internal delegate int _GetInt32(string pchSection, string pchSettingsKey, int nDefaultValue, ref EVRSettingsError peError);
+ internal delegate void _SetFloat(string pchSection, string pchSettingsKey, float flValue, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
- internal _GetInt32 GetInt32;
+ internal _SetFloat SetFloat;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
- internal delegate void _SetInt32(string pchSection, string pchSettingsKey, int nValue, ref EVRSettingsError peError);
+ internal delegate void _SetString(string pchSection, string pchSettingsKey, string pchValue, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
- internal _SetInt32 SetInt32;
+ internal _SetString SetString;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
- internal delegate float _GetFloat(string pchSection, string pchSettingsKey, float flDefaultValue, ref EVRSettingsError peError);
+ internal delegate bool _GetBool(string pchSection, string pchSettingsKey, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
- internal _GetFloat GetFloat;
+ internal _GetBool GetBool;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
- internal delegate void _SetFloat(string pchSection, string pchSettingsKey, float flValue, ref EVRSettingsError peError);
+ internal delegate int _GetInt32(string pchSection, string pchSettingsKey, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
- internal _SetFloat SetFloat;
+ internal _GetInt32 GetInt32;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
- internal delegate void _GetString(string pchSection, string pchSettingsKey, string pchValue, uint unValueLen, string pchDefaultValue, ref EVRSettingsError peError);
+ internal delegate float _GetFloat(string pchSection, string pchSettingsKey, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
- internal _GetString GetString;
+ internal _GetFloat GetFloat;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
- internal delegate void _SetString(string pchSection, string pchSettingsKey, string pchValue, ref EVRSettingsError peError);
+ internal delegate void _GetString(string pchSection, string pchSettingsKey, System.Text.StringBuilder pchValue, uint unValueLen, ref EVRSettingsError peError);
[MarshalAs(UnmanagedType.FunctionPtr)]
- internal _SetString SetString;
+ internal _GetString GetString;
[UnmanagedFunctionPointer(CallingConvention.StdCall)]
internal delegate void _RemoveSection(string pchSection, ref EVRSettingsError peError);
@@ -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,40 +2761,40 @@ 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)
+ public void SetFloat(string pchSection,string pchSettingsKey,float flValue,ref EVRSettingsError peError)
{
- float result = FnTable.GetFloat(pchSection,pchSettingsKey,flDefaultValue,ref peError);
+ FnTable.SetFloat(pchSection,pchSettingsKey,flValue,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 void SetFloat(string pchSection,string pchSettingsKey,float flValue,ref EVRSettingsError peError)
+ public int GetInt32(string pchSection,string pchSettingsKey,ref EVRSettingsError peError)
{
- FnTable.SetFloat(pchSection,pchSettingsKey,flValue,ref peError);
+ int result = FnTable.GetInt32(pchSection,pchSettingsKey,ref peError);
+ return result;
}
- public void GetString(string pchSection,string pchSettingsKey,string pchValue,uint unValueLen,string pchDefaultValue,ref EVRSettingsError peError)
+ public float GetFloat(string pchSection,string pchSettingsKey,ref EVRSettingsError peError)
{
- FnTable.GetString(pchSection,pchSettingsKey,pchValue,unValueLen,pchDefaultValue,ref peError);
+ float result = FnTable.GetFloat(pchSection,pchSettingsKey,ref peError);
+ return result;
}
- public void SetString(string pchSection,string pchSettingsKey,string pchValue,ref EVRSettingsError peError)
+ public void GetString(string pchSection,string pchSettingsKey,System.Text.StringBuilder pchValue,uint unValueLen,ref EVRSettingsError peError)
{
- FnTable.SetString(pchSection,pchSettingsKey,pchValue,ref peError);
+ FnTable.GetString(pchSection,pchSettingsKey,pchValue,unValueLen,ref peError);
}
public void RemoveSection(string pchSection,ref EVRSettingsError 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)
diff --git a/examples/ThirdPartyLibs/openvr/headers/openvr_api.json b/examples/ThirdPartyLibs/openvr/headers/openvr_api.json
index c72b2c415..832e8646b 100644
--- a/examples/ThirdPartyLibs/openvr/headers/openvr_api.json
+++ b/examples/ThirdPartyLibs/openvr/headers/openvr_api.json
@@ -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"}
,{
@@ -741,12 +787,6 @@
,{
"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"}
,{
"constname": "k_pch_SteamVR_DirectModeEdidVid_Int32","consttype": "const char *const", "constval": "directModeEdidVid"}
@@ -773,6 +813,18 @@
,{
"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"}
,{
"constname": "k_pch_Lighthouse_DisableIMU_Bool","consttype": "const char *const", "constval": "disableimu"}
@@ -783,12 +835,6 @@
,{
"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"}
,{
"constname": "k_pch_Null_Section","consttype": "const char *const", "constval": "driver_null"}
@@ -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"}
,{
@@ -893,6 +941,8 @@
,{
"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"}
,{
"constname": "k_pch_audio_OnPlaybackDevice_String","consttype": "const char *const", "constval": "onPlaybackDevice"}
@@ -907,9 +957,29 @@
,{
"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 *"},
@@ -1631,6 +1724,52 @@
]
}
,{
+ "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",
"returntype": "vr::EVRApplicationError",
@@ -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"}
]
}
@@ -1701,6 +1840,15 @@
}
,{
"classname": "vr::IVRApplications",
+ "methodname": "LaunchApplicationFromMimeType",
+ "returntype": "vr::EVRApplicationError",
+ "params": [
+{ "paramname": "pchMimeType" ,"paramtype": "const char *"},
+{ "paramname": "pchArgs" ,"paramtype": "const char *"}
+ ]
+}
+,{
+ "classname": "vr::IVRApplications",
"methodname": "LaunchDashboardOverlay",
"returntype": "vr::EVRApplicationError",
"params": [
@@ -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 *"}
]
@@ -1791,6 +1939,55 @@
}
,{
"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",
"returntype": "vr::EVRApplicationError",
"params": [
@@ -2269,21 +2466,6 @@
}
,{
"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",
"returntype": "vr::EVRCompositorError",
"params": [
@@ -2488,6 +2670,42 @@
}
,{
"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",
"returntype": "vr::EVROverlayError",
"params": [
@@ -3165,91 +3383,87 @@
}
,{
"classname": "vr::IVRSettings",
- "methodname": "GetBool",
- "returntype": "bool",
+ "methodname": "SetBool",
+ "returntype": "void",
"params": [
{ "paramname": "pchSection" ,"paramtype": "const char *"},
{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"},
-{ "paramname": "bDefaultValue" ,"paramtype": "bool"},
+{ "paramname": "bValue" ,"paramtype": "bool"},
{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"}
]
}
,{
"classname": "vr::IVRSettings",
- "methodname": "SetBool",
+ "methodname": "SetInt32",
"returntype": "void",
"params": [
{ "paramname": "pchSection" ,"paramtype": "const char *"},
{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"},
-{ "paramname": "bValue" ,"paramtype": "bool"},
+{ "paramname": "nValue" ,"paramtype": "int32_t"},
{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"}
]
}
,{
"classname": "vr::IVRSettings",
- "methodname": "GetInt32",
- "returntype": "int32_t",
+ "methodname": "SetFloat",
+ "returntype": "void",
"params": [
{ "paramname": "pchSection" ,"paramtype": "const char *"},
{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"},
-{ "paramname": "nDefaultValue" ,"paramtype": "int32_t"},
+{ "paramname": "flValue" ,"paramtype": "float"},
{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"}
]
}
,{
"classname": "vr::IVRSettings",
- "methodname": "SetInt32",
+ "methodname": "SetString",
"returntype": "void",
"params": [
{ "paramname": "pchSection" ,"paramtype": "const char *"},
{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"},
-{ "paramname": "nValue" ,"paramtype": "int32_t"},
+{ "paramname": "pchValue" ,"paramtype": "const char *"},
{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"}
]
}
,{
"classname": "vr::IVRSettings",
- "methodname": "GetFloat",
- "returntype": "float",
+ "methodname": "GetBool",
+ "returntype": "bool",
"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",
- "returntype": "void",
+ "methodname": "GetInt32",
+ "returntype": "int32_t",
"params": [
{ "paramname": "pchSection" ,"paramtype": "const char *"},
{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"},
-{ "paramname": "flValue" ,"paramtype": "float"},
{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"}
]
}
,{
"classname": "vr::IVRSettings",
- "methodname": "GetString",
- "returntype": "void",
+ "methodname": "GetFloat",
+ "returntype": "float",
"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",
+ "methodname": "GetString",
"returntype": "void",
"params": [
{ "paramname": "pchSection" ,"paramtype": "const char *"},
{ "paramname": "pchSettingsKey" ,"paramtype": "const char *"},
-{ "paramname": "pchValue" ,"paramtype": "const char *"},
+{ "paramname": "pchValue" ,"out_string": " " ,"paramtype": "char *"},
+{ "paramname": "unValueLen" ,"paramtype": "uint32_t"},
{ "paramname": "peError" ,"paramtype": "vr::EVRSettingsError *"}
]
}
@@ -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"}
+ ]
+}
]
} \ No newline at end of file
diff --git a/examples/ThirdPartyLibs/openvr/headers/openvr_capi.h b/examples/ThirdPartyLibs/openvr/headers/openvr_capi.h
index 76eafd4d6..fae48f88c 100644
--- a/examples/ThirdPartyLibs/openvr/headers/openvr_capi.h
+++ b/examples/ThirdPartyLibs/openvr/headers/openvr_capi.h
@@ -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
diff --git a/examples/ThirdPartyLibs/openvr/headers/openvr_driver.h b/examples/ThirdPartyLibs/openvr/headers/openvr_driver.h
index 3f2a21df4..643c1172c 100644
--- a/examples/ThirdPartyLibs/openvr/headers/openvr_driver.h
+++ b/examples/ThirdPartyLibs/openvr/headers/openvr_driver.h
@@ -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
@@ -1269,6 +1385,21 @@ namespace vr
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";
}
diff --git a/examples/ThirdPartyLibs/openvr/lib/linux32/libopenvr_api.so b/examples/ThirdPartyLibs/openvr/lib/linux32/libopenvr_api.so
deleted file mode 100644
index 27da01cbe..000000000
--- a/examples/ThirdPartyLibs/openvr/lib/linux32/libopenvr_api.so
+++ /dev/null
Binary files differ
diff --git a/examples/ThirdPartyLibs/openvr/lib/linux64/libopenvr_api.so b/examples/ThirdPartyLibs/openvr/lib/linux64/libopenvr_api.so
index 52fd2271b..d8ddc31c6 100644
--- a/examples/ThirdPartyLibs/openvr/lib/linux64/libopenvr_api.so
+++ b/examples/ThirdPartyLibs/openvr/lib/linux64/libopenvr_api.so
Binary files differ
diff --git a/examples/ThirdPartyLibs/openvr/lib/win32/openvr_api.lib b/examples/ThirdPartyLibs/openvr/lib/win32/openvr_api.lib
index 45a41aeb0..8322d9c3b 100644
--- a/examples/ThirdPartyLibs/openvr/lib/win32/openvr_api.lib
+++ b/examples/ThirdPartyLibs/openvr/lib/win32/openvr_api.lib
Binary files differ
diff --git a/examples/ThirdPartyLibs/openvr/lib/win64/openvr_api.lib b/examples/ThirdPartyLibs/openvr/lib/win64/openvr_api.lib
index 12344317a..3ede69605 100644
--- a/examples/ThirdPartyLibs/openvr/lib/win64/openvr_api.lib
+++ b/examples/ThirdPartyLibs/openvr/lib/win64/openvr_api.lib
Binary files differ
diff --git a/examples/pybullet/quadruped.py b/examples/pybullet/quadruped.py
index a78d7ed40..d4d4838bd 100644
--- a/examples/pybullet/quadruped.py
+++ b/examples/pybullet/quadruped.py
@@ -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()
+